From 5057b172cc25d3110432fa6f45a0f56b51a6fcba Mon Sep 17 00:00:00 2001 From: Octi Zhang Date: Fri, 6 Feb 2026 11:15:36 -0800 Subject: [PATCH 01/46] working commit --- apps/isaaclab.python.kit | 1 - apps/isaacsim_5/isaaclab.python.kit | 1 - .../source/how-to/optimize_stage_creation.rst | 3 +- .../benchmarks/benchmark_view_comparison.py | 3 +- scripts/demos/bin_packing.py | 3 +- scripts/demos/bipeds.py | 3 +- scripts/demos/deformables.py | 3 +- scripts/demos/hands.py | 3 +- scripts/demos/markers.py | 3 +- scripts/demos/multi_asset.py | 3 +- scripts/demos/procedural_terrain.py | 3 +- scripts/demos/quadcopter.py | 5 +- scripts/demos/quadrupeds.py | 3 +- scripts/demos/sensors/cameras.py | 3 +- scripts/demos/sensors/contact_sensor.py | 3 +- .../demos/sensors/frame_transformer_sensor.py | 3 +- scripts/demos/sensors/imu_sensor.py | 3 +- scripts/demos/sensors/multi_mesh_raycaster.py | 3 +- .../sensors/multi_mesh_raycaster_camera.py | 3 +- scripts/demos/sensors/raycaster_sensor.py | 3 +- scripts/tools/check_instanceable.py | 3 +- scripts/tutorials/00_sim/create_empty.py | 3 +- scripts/tutorials/00_sim/launch_app.py | 3 +- scripts/tutorials/00_sim/log_time.py | 3 +- scripts/tutorials/00_sim/spawn_prims.py | 3 +- .../04_sensors/add_sensors_on_robot.py | 3 +- .../04_sensors/run_frame_transformer.py | 3 +- .../tutorials/04_sensors/run_usd_camera.py | 4 +- .../tutorials/05_controllers/run_diff_ik.py | 3 +- scripts/tutorials/05_controllers/run_osc.py | 3 +- source/isaaclab/isaaclab/assets/asset_base.py | 71 +- .../isaaclab/isaaclab/envs/direct_marl_env.py | 20 +- .../isaaclab/isaaclab/envs/direct_rl_env.py | 40 +- .../isaaclab/envs/manager_based_env.py | 30 +- .../isaaclab/envs/manager_based_rl_env.py | 12 +- .../isaaclab/envs/ui/base_env_window.py | 14 +- source/isaaclab/isaaclab/physics/__init__.py | 16 + .../isaaclab/physics/physics_manager.py | 335 +++++ .../isaaclab/physics/physics_manager_cfg.py | 62 + .../isaaclab/sensors/ray_caster/ray_caster.py | 4 +- .../isaaclab/isaaclab/sensors/sensor_base.py | 59 +- source/isaaclab/isaaclab/sim/__init__.py | 2 +- .../isaaclab/isaaclab/sim/simulation_cfg.py | 334 +---- .../isaaclab/sim/simulation_context.py | 1299 ++++------------- .../isaaclab/isaaclab/visualizers/__init__.py | 27 + .../isaaclab/visualizers/visualizer.py | 107 ++ .../isaaclab/visualizers/visualizer_cfg.py | 82 ++ .../test/app/test_non_headless_launch.py | 3 +- .../test/assets/check_external_force.py | 3 +- .../test/assets/check_fixed_base_assets.py | 3 +- .../test/controllers/test_differential_ik.py | 3 +- .../controllers/test_operational_space.py | 3 +- .../isaaclab/test/devices/check_keyboard.py | 3 +- .../test/envs/test_env_rendering_logic.py | 7 +- .../test/managers/test_observation_manager.py | 3 +- .../test/markers/check_markers_visibility.py | 3 +- .../markers/test_visualization_markers.py | 3 +- .../test/scene/check_interactive_scene.py | 3 +- source/isaaclab/test/sensors/test_camera.py | 3 +- .../test_multi_mesh_ray_caster_camera.py | 3 +- .../test/sensors/test_multi_tiled_camera.py | 3 +- .../test/sensors/test_ray_caster_camera.py | 3 +- .../isaaclab/test/sensors/test_sensor_base.py | 3 +- .../test/sensors/test_tiled_camera.py | 3 +- source/isaaclab/test/sim/check_meshes.py | 3 +- .../isaaclab/test/sim/test_mesh_converter.py | 3 +- .../isaaclab/test/sim/test_mjcf_converter.py | 3 +- source/isaaclab/test/sim/test_schemas.py | 3 +- .../test/sim/test_simulation_context.py | 1 + .../sim/test_simulation_stage_in_memory.py | 6 +- .../test/sim/test_spawn_from_files.py | 3 +- source/isaaclab/test/sim/test_spawn_lights.py | 3 +- .../isaaclab/test/sim/test_spawn_materials.py | 3 +- source/isaaclab/test/sim/test_spawn_meshes.py | 3 +- .../isaaclab/test/sim/test_spawn_sensors.py | 3 +- source/isaaclab/test/sim/test_spawn_shapes.py | 3 +- .../isaaclab/test/sim/test_spawn_wrappers.py | 3 +- .../isaaclab/test/sim/test_urdf_converter.py | 3 +- .../test/sim/test_views_xform_prim.py | 3 +- .../check_scene_xr_visualization.py | 3 +- .../test/sensors/test_visuotactile_sensor.py | 3 +- .../assets/articulation/articulation.py | 2 +- .../assets/articulation/articulation_data.py | 2 +- .../deformable_object/deformable_object.py | 2 +- .../assets/rigid_object/rigid_object.py | 2 +- .../assets/rigid_object/rigid_object_data.py | 2 +- .../rigid_object_collection.py | 2 +- .../rigid_object_collection_data.py | 2 +- .../isaaclab_physx/physics/__init__.py | 16 + .../isaaclab_physx/physics/physx_manager.py | 563 +++++++ .../physics/physx_manager_cfg.py | 225 +++ .../sensors/contact_sensor/contact_sensor.py | 2 +- .../frame_transformer/frame_transformer.py | 2 +- .../isaaclab_physx/sensors/imu/imu.py | 2 +- .../isaaclab_physx/visualizers/__init__.py | 51 + .../visualizers/physx_ov_visualizer.py | 759 ++++++++++ .../visualizers/physx_ov_visualizer_cfg.py | 83 ++ .../test/sensors/check_contact_sensor.py | 3 +- .../test/sensors/test_contact_sensor.py | 7 +- .../test/sensors/test_frame_transformer.py | 3 +- .../isaaclab_physx/test/sensors/test_imu.py | 4 +- .../allegro_hand/allegro_hand_env_cfg.py | 15 +- .../isaaclab_tasks/direct/ant/ant_env.py | 3 +- .../direct/automate/disassembly_env.py | 2 +- .../cart_double_pendulum_env.py | 3 +- .../direct/cartpole/cartpole_camera_env.py | 3 +- .../direct/cartpole/cartpole_env.py | 3 +- .../direct/humanoid/humanoid_env.py | 3 +- .../tasks/direct_multi-agent/env_cfg | 3 +- .../tasks/direct_single-agent/env_cfg | 3 +- 110 files changed, 2903 insertions(+), 1579 deletions(-) create mode 100644 source/isaaclab/isaaclab/physics/__init__.py create mode 100644 source/isaaclab/isaaclab/physics/physics_manager.py create mode 100644 source/isaaclab/isaaclab/physics/physics_manager_cfg.py create mode 100644 source/isaaclab/isaaclab/visualizers/__init__.py create mode 100644 source/isaaclab/isaaclab/visualizers/visualizer.py create mode 100644 source/isaaclab/isaaclab/visualizers/visualizer_cfg.py create mode 100644 source/isaaclab_physx/isaaclab_physx/physics/__init__.py create mode 100644 source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py create mode 100644 source/isaaclab_physx/isaaclab_physx/physics/physx_manager_cfg.py create mode 100644 source/isaaclab_physx/isaaclab_physx/visualizers/__init__.py create mode 100644 source/isaaclab_physx/isaaclab_physx/visualizers/physx_ov_visualizer.py create mode 100644 source/isaaclab_physx/isaaclab_physx/visualizers/physx_ov_visualizer_cfg.py diff --git a/apps/isaaclab.python.kit b/apps/isaaclab.python.kit index 66480ea3791..82d55443687 100644 --- a/apps/isaaclab.python.kit +++ b/apps/isaaclab.python.kit @@ -17,7 +17,6 @@ keywords = ["experience", "app", "usd"] "isaacsim.core.api" = {} "isaacsim.core.cloner" = {} "isaacsim.core.nodes" = {} -"isaacsim.core.simulation_manager" = {} "isaacsim.core.throttling" = {} "isaacsim.core.utils" = {} "isaacsim.core.version" = {} diff --git a/apps/isaacsim_5/isaaclab.python.kit b/apps/isaacsim_5/isaaclab.python.kit index 358f96773cc..4c0f962a639 100644 --- a/apps/isaacsim_5/isaaclab.python.kit +++ b/apps/isaacsim_5/isaaclab.python.kit @@ -17,7 +17,6 @@ keywords = ["experience", "app", "usd"] "isaacsim.core.api" = {} "isaacsim.core.cloner" = {} "isaacsim.core.nodes" = {} -"isaacsim.core.simulation_manager" = {} "isaacsim.core.throttling" = {} "isaacsim.core.utils" = {} "isaacsim.core.version" = {} diff --git a/docs/source/how-to/optimize_stage_creation.rst b/docs/source/how-to/optimize_stage_creation.rst index b262878d667..2131af0c5eb 100644 --- a/docs/source/how-to/optimize_stage_creation.rst +++ b/docs/source/how-to/optimize_stage_creation.rst @@ -60,8 +60,7 @@ be called after the stage is created. sim = SimulationContext(cfg=SimulationCfg(create_stage_in_memory=True)) # grab stage in memory and set stage context - stage_in_memory = sim.get_initial_stage() - with stage_utils.use_stage(stage_in_memory): + with stage_utils.use_stage(sim.stage): # create cartpole scene scene_cfg = CartpoleSceneCfg(num_envs=1024) scene = InteractiveScene(scene_cfg) diff --git a/scripts/benchmarks/benchmark_view_comparison.py b/scripts/benchmarks/benchmark_view_comparison.py index 82e48a7d981..9302545285f 100644 --- a/scripts/benchmarks/benchmark_view_comparison.py +++ b/scripts/benchmarks/benchmark_view_comparison.py @@ -73,6 +73,7 @@ from isaacsim.core.simulation_manager import SimulationManager import isaaclab.sim as sim_utils +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sim.views import XformPrimView @@ -98,7 +99,7 @@ def benchmark_view(view_type: str, num_iterations: int) -> tuple[dict[str, float sim_utils.create_new_stage() # Create simulation context start_time = time.perf_counter() - sim_cfg = sim_utils.SimulationCfg(dt=0.01, device=args_cli.device, use_fabric=(view_type == "xform_fabric")) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics_manager_cfg=PhysxManagerCfg(dt=0.01, use_fabric=(view_type == "xform_fabric"))) sim = sim_utils.SimulationContext(sim_cfg) stage = sim_utils.get_current_stage() diff --git a/scripts/demos/bin_packing.py b/scripts/demos/bin_packing.py index e23dc0ddcde..d72faa0dd7a 100644 --- a/scripts/demos/bin_packing.py +++ b/scripts/demos/bin_packing.py @@ -46,6 +46,7 @@ import torch import isaaclab.sim as sim_utils +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg import isaaclab.utils.math as math_utils from isaaclab.assets import AssetBaseCfg, RigidObjectCfg, RigidObjectCollection, RigidObjectCollectionCfg from isaaclab.scene import InteractiveScene, InteractiveSceneCfg @@ -327,7 +328,7 @@ def main() -> None: None: The function drives the simulation for its side-effects. """ # Load kit helper - sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics_manager_cfg=PhysxManagerCfg(dt=0.005)) sim = SimulationContext(sim_cfg) # Set main camera sim.set_camera_view((2.5, 0.0, 4.0), (0.0, 0.0, 2.0)) diff --git a/scripts/demos/bipeds.py b/scripts/demos/bipeds.py index 91421c105ff..2995d5ffc6c 100644 --- a/scripts/demos/bipeds.py +++ b/scripts/demos/bipeds.py @@ -35,6 +35,7 @@ import torch import isaaclab.sim as sim_utils +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.assets import Articulation from isaaclab.sim import SimulationContext @@ -114,7 +115,7 @@ def run_simulator(sim: sim_utils.SimulationContext, robots: list[Articulation], def main(): """Main function.""" # Load kit helper - sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics_manager_cfg=PhysxManagerCfg(dt=0.005)) sim = SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[3.0, 0.0, 2.25], target=[0.0, 0.0, 1.0]) diff --git a/scripts/demos/deformables.py b/scripts/demos/deformables.py index 9b9a962c26d..3a99c4116c6 100644 --- a/scripts/demos/deformables.py +++ b/scripts/demos/deformables.py @@ -38,6 +38,7 @@ import tqdm import isaaclab.sim as sim_utils +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.assets import DeformableObject, DeformableObjectCfg @@ -178,7 +179,7 @@ def run_simulator(sim: sim_utils.SimulationContext, entities: dict[str, Deformab def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(dt=0.01, device=args_cli.device) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics_manager_cfg=PhysxManagerCfg(dt=0.01)) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view([4.0, 4.0, 3.0], [0.5, 0.5, 0.0]) diff --git a/scripts/demos/hands.py b/scripts/demos/hands.py index a0fa04e0fbf..c70a7258911 100644 --- a/scripts/demos/hands.py +++ b/scripts/demos/hands.py @@ -36,6 +36,7 @@ import torch import isaaclab.sim as sim_utils +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.assets import Articulation ## @@ -143,7 +144,7 @@ def run_simulator(sim: sim_utils.SimulationContext, entities: dict[str, Articula def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(dt=0.01, device=args_cli.device) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics_manager_cfg=PhysxManagerCfg(dt=0.01)) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[0.0, -0.5, 1.5], target=[0.0, -0.2, 0.5]) diff --git a/scripts/demos/markers.py b/scripts/demos/markers.py index 6152dcf5226..f700a12ad0f 100644 --- a/scripts/demos/markers.py +++ b/scripts/demos/markers.py @@ -34,6 +34,7 @@ import torch import isaaclab.sim as sim_utils +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.markers import VisualizationMarkers, VisualizationMarkersCfg from isaaclab.sim import SimulationContext from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR, ISAACLAB_NUCLEUS_DIR @@ -94,7 +95,7 @@ def define_markers() -> VisualizationMarkers: def main(): """Main function.""" # Load kit helper - sim_cfg = sim_utils.SimulationCfg(dt=0.01, device=args_cli.device) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics_manager_cfg=PhysxManagerCfg(dt=0.01)) sim = SimulationContext(sim_cfg) # Set main camera sim.set_camera_view([0.0, 18.0, 12.0], [0.0, 3.0, 0.0]) diff --git a/scripts/demos/multi_asset.py b/scripts/demos/multi_asset.py index d104eb161d3..a8551687473 100644 --- a/scripts/demos/multi_asset.py +++ b/scripts/demos/multi_asset.py @@ -40,6 +40,7 @@ from pxr import Gf, Sdf import isaaclab.sim as sim_utils +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.assets import ( Articulation, ArticulationCfg, @@ -275,7 +276,7 @@ def run_simulator(sim: SimulationContext, scene: InteractiveScene): def main(): """Main function.""" # Load kit helper - sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics_manager_cfg=PhysxManagerCfg(dt=0.005)) sim = SimulationContext(sim_cfg) # Set main camera sim.set_camera_view([2.5, 0.0, 4.0], [0.0, 0.0, 2.0]) diff --git a/scripts/demos/procedural_terrain.py b/scripts/demos/procedural_terrain.py index f0a2fb4e2ef..4885f3a76c9 100644 --- a/scripts/demos/procedural_terrain.py +++ b/scripts/demos/procedural_terrain.py @@ -70,6 +70,7 @@ import torch import isaaclab.sim as sim_utils +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.assets import AssetBase from isaaclab.markers import VisualizationMarkers, VisualizationMarkersCfg from isaaclab.terrains import FlatPatchSamplingCfg, TerrainImporter, TerrainImporterCfg @@ -154,7 +155,7 @@ def run_simulator(sim: sim_utils.SimulationContext, entities: dict[str, AssetBas def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(dt=0.01, device=args_cli.device) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics_manager_cfg=PhysxManagerCfg(dt=0.01)) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[5.0, 5.0, 5.0], target=[0.0, 0.0, 0.0]) diff --git a/scripts/demos/quadcopter.py b/scripts/demos/quadcopter.py index ffd030bfb11..10b83bf3415 100644 --- a/scripts/demos/quadcopter.py +++ b/scripts/demos/quadcopter.py @@ -35,6 +35,7 @@ import torch import isaaclab.sim as sim_utils +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.assets import Articulation from isaaclab.sim import SimulationContext @@ -47,7 +48,7 @@ def main(): """Main function.""" # Load kit helper - sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics_manager_cfg=PhysxManagerCfg(dt=0.005)) sim = SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[0.5, 0.5, 1.0], target=[0.0, 0.0, 0.5]) @@ -73,7 +74,7 @@ def main(): # Fetch relevant parameters to make the quadcopter hover in place prop_body_ids = robot.find_bodies("m.*_prop")[0] robot_mass = robot.root_view.get_masses().sum() - gravity = torch.tensor(sim.cfg.gravity, device=sim.device).norm() + gravity = torch.tensor(sim.cfg.physics_manager_cfg.gravity, device=sim.device).norm() # Now we are ready! print("[INFO]: Setup complete...") diff --git a/scripts/demos/quadrupeds.py b/scripts/demos/quadrupeds.py index b9935de30da..091844ba27d 100644 --- a/scripts/demos/quadrupeds.py +++ b/scripts/demos/quadrupeds.py @@ -36,6 +36,7 @@ import torch import isaaclab.sim as sim_utils +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.assets import Articulation ## @@ -170,7 +171,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim = sim_utils.SimulationContext(sim_utils.SimulationCfg(dt=0.01)) + sim = sim_utils.SimulationContext(sim_utils.SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01))) # Set main camera sim.set_camera_view(eye=[2.5, 2.5, 2.5], target=[0.0, 0.0, 0.0]) # design scene diff --git a/scripts/demos/sensors/cameras.py b/scripts/demos/sensors/cameras.py index 83214f7e4cf..6caa2a92b9b 100644 --- a/scripts/demos/sensors/cameras.py +++ b/scripts/demos/sensors/cameras.py @@ -44,6 +44,7 @@ import torch import isaaclab.sim as sim_utils +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.assets import ArticulationCfg, AssetBaseCfg from isaaclab.scene import InteractiveScene, InteractiveSceneCfg from isaaclab.sensors import CameraCfg, RayCasterCameraCfg, TiledCameraCfg @@ -280,7 +281,7 @@ def run_simulator(sim: sim_utils.SimulationContext, scene: InteractiveScene): def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device, use_fabric=not args_cli.disable_fabric) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics_manager_cfg=PhysxManagerCfg(dt=0.005, use_fabric=not args_cli.disable_fabric)) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) diff --git a/scripts/demos/sensors/contact_sensor.py b/scripts/demos/sensors/contact_sensor.py index 0ee672ec16a..bea383c7739 100644 --- a/scripts/demos/sensors/contact_sensor.py +++ b/scripts/demos/sensors/contact_sensor.py @@ -26,6 +26,7 @@ import torch import isaaclab.sim as sim_utils +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.assets import AssetBaseCfg, RigidObjectCfg from isaaclab.scene import InteractiveScene, InteractiveSceneCfg from isaaclab.sensors import ContactSensorCfg @@ -154,7 +155,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics_manager_cfg=PhysxManagerCfg(dt=0.005)) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) diff --git a/scripts/demos/sensors/frame_transformer_sensor.py b/scripts/demos/sensors/frame_transformer_sensor.py index 8827b23cea7..12658679ee5 100644 --- a/scripts/demos/sensors/frame_transformer_sensor.py +++ b/scripts/demos/sensors/frame_transformer_sensor.py @@ -24,6 +24,7 @@ import torch import isaaclab.sim as sim_utils +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.assets import AssetBaseCfg, RigidObjectCfg from isaaclab.scene import InteractiveScene, InteractiveSceneCfg from isaaclab.sensors import FrameTransformerCfg @@ -148,7 +149,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics_manager_cfg=PhysxManagerCfg(dt=0.005)) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) diff --git a/scripts/demos/sensors/imu_sensor.py b/scripts/demos/sensors/imu_sensor.py index af649fd94a9..192dc6eeab3 100644 --- a/scripts/demos/sensors/imu_sensor.py +++ b/scripts/demos/sensors/imu_sensor.py @@ -26,6 +26,7 @@ import torch import isaaclab.sim as sim_utils +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.assets import AssetBaseCfg from isaaclab.scene import InteractiveScene, InteractiveSceneCfg from isaaclab.sensors import ImuCfg @@ -121,7 +122,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics_manager_cfg=PhysxManagerCfg(dt=0.005)) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) diff --git a/scripts/demos/sensors/multi_mesh_raycaster.py b/scripts/demos/sensors/multi_mesh_raycaster.py index 07b36573501..04efd09d9f4 100644 --- a/scripts/demos/sensors/multi_mesh_raycaster.py +++ b/scripts/demos/sensors/multi_mesh_raycaster.py @@ -52,6 +52,7 @@ from pxr import Gf, Sdf import isaaclab.sim as sim_utils +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.assets import Articulation, AssetBaseCfg, RigidObjectCfg from isaaclab.markers.config import VisualizationMarkersCfg from isaaclab.scene import InteractiveScene, InteractiveSceneCfg @@ -277,7 +278,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics_manager_cfg=PhysxManagerCfg(dt=0.005)) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) diff --git a/scripts/demos/sensors/multi_mesh_raycaster_camera.py b/scripts/demos/sensors/multi_mesh_raycaster_camera.py index 8ef3a188f3d..dd376499984 100644 --- a/scripts/demos/sensors/multi_mesh_raycaster_camera.py +++ b/scripts/demos/sensors/multi_mesh_raycaster_camera.py @@ -52,6 +52,7 @@ from pxr import Gf, Sdf import isaaclab.sim as sim_utils +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.assets import Articulation, AssetBaseCfg, RigidObjectCfg from isaaclab.markers.config import VisualizationMarkersCfg from isaaclab.scene import InteractiveScene, InteractiveSceneCfg @@ -303,7 +304,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics_manager_cfg=PhysxManagerCfg(dt=0.005)) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) diff --git a/scripts/demos/sensors/raycaster_sensor.py b/scripts/demos/sensors/raycaster_sensor.py index 02c55222e83..7322df0c883 100644 --- a/scripts/demos/sensors/raycaster_sensor.py +++ b/scripts/demos/sensors/raycaster_sensor.py @@ -25,6 +25,7 @@ import torch import isaaclab.sim as sim_utils +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.assets import AssetBaseCfg from isaaclab.scene import InteractiveScene, InteractiveSceneCfg from isaaclab.sensors.ray_caster import RayCasterCfg, patterns @@ -139,7 +140,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics_manager_cfg=PhysxManagerCfg(dt=0.005)) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) diff --git a/scripts/tools/check_instanceable.py b/scripts/tools/check_instanceable.py index d9ce51497d1..b3176c24c24 100644 --- a/scripts/tools/check_instanceable.py +++ b/scripts/tools/check_instanceable.py @@ -67,6 +67,7 @@ from isaacsim.core.cloner import GridCloner import isaaclab.sim as sim_utils +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sim import SimulationCfg, SimulationContext from isaaclab.utils import Timer from isaaclab.utils.assets import check_file_path @@ -78,7 +79,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(SimulationCfg(dt=0.01)) + sim = SimulationContext(SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01))) # get stage handle stage = sim_utils.get_current_stage() diff --git a/scripts/tutorials/00_sim/create_empty.py b/scripts/tutorials/00_sim/create_empty.py index 6fa283a68f1..5f207b82b69 100644 --- a/scripts/tutorials/00_sim/create_empty.py +++ b/scripts/tutorials/00_sim/create_empty.py @@ -31,6 +31,7 @@ """Rest everything follows.""" +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sim import SimulationCfg, SimulationContext @@ -38,7 +39,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim_cfg = SimulationCfg(dt=0.01) + sim_cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01)) sim = SimulationContext(sim_cfg) # Set main camera sim.set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0]) diff --git a/scripts/tutorials/00_sim/launch_app.py b/scripts/tutorials/00_sim/launch_app.py index 1622d3ba956..7437b6cd580 100644 --- a/scripts/tutorials/00_sim/launch_app.py +++ b/scripts/tutorials/00_sim/launch_app.py @@ -42,6 +42,7 @@ """Rest everything follows.""" import isaaclab.sim as sim_utils +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg def design_scene(): @@ -70,7 +71,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(dt=0.01, device=args_cli.device) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics_manager_cfg=PhysxManagerCfg(dt=0.01)) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view([2.0, 0.0, 2.5], [-0.5, 0.0, 0.5]) diff --git a/scripts/tutorials/00_sim/log_time.py b/scripts/tutorials/00_sim/log_time.py index 2e4445c3d47..25b6964c46b 100644 --- a/scripts/tutorials/00_sim/log_time.py +++ b/scripts/tutorials/00_sim/log_time.py @@ -34,6 +34,7 @@ """Rest everything follows.""" +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sim import SimulationCfg, SimulationContext @@ -53,7 +54,7 @@ def main(): print(f"[INFO] Logging experiment to directory: {log_dir_path}") # Initialize the simulation context - sim_cfg = SimulationCfg(dt=0.01) + sim_cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01)) sim = SimulationContext(sim_cfg) # Set main camera sim.set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0]) diff --git a/scripts/tutorials/00_sim/spawn_prims.py b/scripts/tutorials/00_sim/spawn_prims.py index 7c120bd308d..1caa8396c79 100644 --- a/scripts/tutorials/00_sim/spawn_prims.py +++ b/scripts/tutorials/00_sim/spawn_prims.py @@ -32,6 +32,7 @@ """Rest everything follows.""" import isaaclab.sim as sim_utils +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR @@ -90,7 +91,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(dt=0.01, device=args_cli.device) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics_manager_cfg=PhysxManagerCfg(dt=0.01)) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view([2.0, 0.0, 2.5], [-0.5, 0.0, 0.5]) diff --git a/scripts/tutorials/04_sensors/add_sensors_on_robot.py b/scripts/tutorials/04_sensors/add_sensors_on_robot.py index 5cc6de6778b..c6d784ed943 100644 --- a/scripts/tutorials/04_sensors/add_sensors_on_robot.py +++ b/scripts/tutorials/04_sensors/add_sensors_on_robot.py @@ -43,6 +43,7 @@ import isaaclab.sim as sim_utils from isaaclab.assets import ArticulationCfg, AssetBaseCfg +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.scene import InteractiveScene, InteractiveSceneCfg from isaaclab.sensors import CameraCfg, ContactSensorCfg, RayCasterCfg, patterns from isaaclab.utils import configclass @@ -157,7 +158,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics_manager_cfg=PhysxManagerCfg(dt=0.005)) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) diff --git a/scripts/tutorials/04_sensors/run_frame_transformer.py b/scripts/tutorials/04_sensors/run_frame_transformer.py index d6d12665ada..a6d98da8dc0 100644 --- a/scripts/tutorials/04_sensors/run_frame_transformer.py +++ b/scripts/tutorials/04_sensors/run_frame_transformer.py @@ -43,6 +43,7 @@ from isaaclab.assets import Articulation from isaaclab.markers import VisualizationMarkers from isaaclab.markers.config import FRAME_MARKER_CFG +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sensors import FrameTransformer, FrameTransformerCfg, OffsetCfg from isaaclab.sim import SimulationContext @@ -165,7 +166,7 @@ def run_simulator(sim: sim_utils.SimulationContext, scene_entities: dict): def main(): """Main function.""" # Load kit helper - sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics_manager_cfg=PhysxManagerCfg(dt=0.005)) sim = SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[2.5, 2.5, 2.5], target=[0.0, 0.0, 0.0]) diff --git a/scripts/tutorials/04_sensors/run_usd_camera.py b/scripts/tutorials/04_sensors/run_usd_camera.py index c2462aaaec8..fb57e01b9e7 100644 --- a/scripts/tutorials/04_sensors/run_usd_camera.py +++ b/scripts/tutorials/04_sensors/run_usd_camera.py @@ -196,7 +196,7 @@ def run_simulator(sim: sim_utils.SimulationContext, scene_entities: dict): camera_index = args_cli.camera_id # Create the markers for the --draw option outside of is_running() loop - if sim.has_gui() and args_cli.draw: + if sim.carb_settings.get("/isaaclab/has_gui") and args_cli.draw: cfg = RAY_CASTER_MARKER_CFG.replace(prim_path="/Visuals/CameraPointCloud") cfg.markers["hit"].radius = 0.002 pc_markers = VisualizationMarkers(cfg) @@ -248,7 +248,7 @@ def run_simulator(sim: sim_utils.SimulationContext, scene_entities: dict): rep_writer.write(rep_output) # Draw pointcloud if there is a GUI and --draw has been passed - if sim.has_gui() and args_cli.draw and "distance_to_image_plane" in camera.data.output.keys(): + if sim.carb_settings.get("/isaaclab/has_gui") and args_cli.draw and "distance_to_image_plane" in camera.data.output.keys(): # Derive pointcloud from camera at camera_index pointcloud = create_pointcloud_from_depth( intrinsic_matrix=camera.data.intrinsic_matrices[camera_index], diff --git a/scripts/tutorials/05_controllers/run_diff_ik.py b/scripts/tutorials/05_controllers/run_diff_ik.py index c79ae802d64..6b34660f63a 100644 --- a/scripts/tutorials/05_controllers/run_diff_ik.py +++ b/scripts/tutorials/05_controllers/run_diff_ik.py @@ -42,6 +42,7 @@ import isaaclab.sim as sim_utils from isaaclab.assets import AssetBaseCfg from isaaclab.controllers import DifferentialIKController, DifferentialIKControllerCfg +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.managers import SceneEntityCfg from isaaclab.markers import VisualizationMarkers from isaaclab.markers.config import FRAME_MARKER_CFG @@ -190,7 +191,7 @@ def run_simulator(sim: sim_utils.SimulationContext, scene: InteractiveScene): def main(): """Main function.""" # Load kit helper - sim_cfg = sim_utils.SimulationCfg(dt=0.01, device=args_cli.device) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics_manager_cfg=PhysxManagerCfg(dt=0.01)) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0]) diff --git a/scripts/tutorials/05_controllers/run_osc.py b/scripts/tutorials/05_controllers/run_osc.py index 705dec63bc7..95dbca5ee7f 100644 --- a/scripts/tutorials/05_controllers/run_osc.py +++ b/scripts/tutorials/05_controllers/run_osc.py @@ -41,6 +41,7 @@ import isaaclab.sim as sim_utils from isaaclab.assets import Articulation, AssetBaseCfg from isaaclab.controllers import OperationalSpaceController, OperationalSpaceControllerCfg +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.markers import VisualizationMarkers from isaaclab.markers.config import FRAME_MARKER_CFG from isaaclab.scene import InteractiveScene, InteractiveSceneCfg @@ -462,7 +463,7 @@ def convert_to_task_frame(osc: OperationalSpaceController, command: torch.tensor def main(): """Main function.""" # Load kit helper - sim_cfg = sim_utils.SimulationCfg(dt=0.01, device=args_cli.device) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics_manager_cfg=PhysxManagerCfg(dt=0.01)) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0]) diff --git a/source/isaaclab/isaaclab/assets/asset_base.py b/source/isaaclab/isaaclab/assets/asset_base.py index 8a7fecedbb8..547bfc22708 100644 --- a/source/isaaclab/isaaclab/assets/asset_base.py +++ b/source/isaaclab/isaaclab/assets/asset_base.py @@ -5,7 +5,6 @@ from __future__ import annotations -import builtins import inspect import re import weakref @@ -16,10 +15,10 @@ import torch import omni.kit.app -import omni.timeline -from isaacsim.core.simulation_manager import IsaacEvents, SimulationManager import isaaclab.sim as sim_utils +from isaaclab.physics import PhysicsEvent, PhysicsManager +from isaaclab_physx.physics import IsaacEvents, PhysxManager from isaaclab.sim.utils.stage import get_current_stage if TYPE_CHECKING: @@ -265,7 +264,7 @@ def _debug_vis_callback(self, event): """ def _register_callbacks(self): - """Registers the timeline and prim deletion callbacks.""" + """Registers physics lifecycle and prim deletion callbacks.""" # register simulator callbacks (with weakref safety to avoid crashes on deletion) def safe_callback(callback_name, event, obj_ref): @@ -278,27 +277,24 @@ def safe_callback(callback_name, event, obj_ref): pass # note: use weakref on callbacks to ensure that this object can be deleted when its destructor is called. - # add callbacks for stage play/stop obj_ref = weakref.proxy(self) - timeline_event_stream = omni.timeline.get_timeline_interface().get_timeline_event_stream() - # the order is set to 10 which is arbitrary but should be lower priority than the default order of 0 - # register timeline PLAY event callback (lower priority with order=10) - self._initialize_handle = timeline_event_stream.create_subscription_to_pop_by_type( - int(omni.timeline.TimelineEventType.PLAY), - lambda event, obj_ref=obj_ref: safe_callback("_initialize_callback", event, obj_ref), + # Register PHYSICS_READY callback for initialization (order=10 for lower priority) + self._initialize_handle = PhysxManager.register_callback( + lambda payload, obj_ref=obj_ref: safe_callback("_initialize_callback", payload, obj_ref), + PhysicsEvent.PHYSICS_READY, order=10, ) - # register timeline STOP event callback (lower priority with order=10) - self._invalidate_initialize_handle = timeline_event_stream.create_subscription_to_pop_by_type( - int(omni.timeline.TimelineEventType.STOP), + # Register TIMELINE_STOP callback for invalidation (PhysX-specific) + self._invalidate_initialize_handle = PhysxManager.register_callback( lambda event, obj_ref=obj_ref: safe_callback("_invalidate_initialize_callback", event, obj_ref), + IsaacEvents.TIMELINE_STOP, order=10, ) - # register prim deletion callback - self._prim_deletion_callback_id = SimulationManager.register_callback( + # Register PRIM_DELETION callback (PhysX-specific) + self._prim_deletion_handle = PhysxManager.register_callback( lambda event, obj_ref=obj_ref: safe_callback("_on_prim_deletion", event, obj_ref), - event=IsaacEvents.PRIM_DELETION, + IsaacEvents.PRIM_DELETION, ) def _initialize_callback(self, event): @@ -310,14 +306,14 @@ 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 = PhysicsManager.get_backend() + self._device = PhysicsManager.get_device() # initialize the asset try: self._initialize_impl() except Exception as e: - if builtins.ISAACLAB_CALLBACK_EXCEPTION is None: - builtins.ISAACLAB_CALLBACK_EXCEPTION = e + # Store exception to be raised after callback completes + PhysxManager.store_callback_exception(e) # set flag self._is_initialized = True @@ -328,15 +324,16 @@ def _invalidate_initialize_callback(self, event): self._debug_vis_handle.unsubscribe() self._debug_vis_handle = None - def _on_prim_deletion(self, prim_path: str) -> None: + def _on_prim_deletion(self, event) -> None: """Invalidates and deletes the callbacks when the prim is deleted. Args: - prim_path: The path to the prim that is being deleted. + event: The prim deletion event containing the prim path in payload. - .. note:: + Note: This function is called when the prim is deleted. """ + prim_path = event.payload["prim_path"] if prim_path == "/": self._clear_callbacks() return @@ -346,18 +343,22 @@ def _on_prim_deletion(self, prim_path: str) -> None: if result: self._clear_callbacks() - def _clear_callbacks(self) -> None: - """Clears the callbacks.""" - if self._prim_deletion_callback_id: - SimulationManager.deregister_callback(self._prim_deletion_callback_id) - self._prim_deletion_callback_id = None - if self._initialize_handle: - self._initialize_handle.unsubscribe() + def _clear_callbacks(self, event: Any = None) -> None: + """Clears the callbacks. + + Args: + event: Optional event that triggered the callback (unused but required for event handlers). + """ + if self._initialize_handle is not None: + self._initialize_handle.deregister() self._initialize_handle = None - if self._invalidate_initialize_handle: - self._invalidate_initialize_handle.unsubscribe() + if self._invalidate_initialize_handle is not None: + self._invalidate_initialize_handle.deregister() self._invalidate_initialize_handle = None - # clear debug visualization - if self._debug_vis_handle: + if self._prim_deletion_handle is not None: + self._prim_deletion_handle.deregister() + self._prim_deletion_handle = None + # Clear debug visualization + if self._debug_vis_handle is not None: self._debug_vis_handle.unsubscribe() self._debug_vis_handle = None diff --git a/source/isaaclab/isaaclab/envs/direct_marl_env.py b/source/isaaclab/isaaclab/envs/direct_marl_env.py index 206a4e7c01c..f47f09d537e 100644 --- a/source/isaaclab/isaaclab/envs/direct_marl_env.py +++ b/source/isaaclab/isaaclab/envs/direct_marl_env.py @@ -123,7 +123,7 @@ def __init__(self, cfg: DirectMARLEnvCfg, render_mode: str | None = None, **kwar # generate scene with Timer("[INFO]: Time taken for scene creation", "scene_creation"): # set the stage context for scene creation steps which use the stage - with use_stage(self.sim.get_initial_stage()): + with use_stage(self.sim.stage): self.scene = InteractiveScene(self.cfg.scene) self._setup_scene() attach_stage_to_usd_context() @@ -133,7 +133,7 @@ def __init__(self, cfg: DirectMARLEnvCfg, render_mode: str | None = None, **kwar # viewport is not available in other rendering modes so the function will throw a warning # FIXME: This needs to be fixed in the future when we unify the UI functionalities even for # non-rendering modes. - if self.sim.render_mode >= self.sim.RenderMode.PARTIAL_RENDERING: + if self.sim.carb_settings.get("/isaaclab/has_gui"): self.viewport_camera_controller = ViewportCameraController(self, self.cfg.viewer) else: self.viewport_camera_controller = None @@ -156,7 +156,7 @@ def __init__(self, cfg: DirectMARLEnvCfg, render_mode: str | None = None, **kwar with Timer("[INFO]: Time taken for simulation start", "simulation_start"): # since the reset can trigger callbacks which use the stage, # we need to set the stage context here - with use_stage(self.sim.get_initial_stage()): + with use_stage(self.sim.stage): self.sim.reset() # update scene to pre populate data buffers for assets and sensors. # this is needed for the observation manager to get valid tensors for initialization. @@ -172,7 +172,7 @@ def __init__(self, cfg: DirectMARLEnvCfg, render_mode: str | None = None, **kwar # extend UI elements # we need to do this here after all the managers are initialized # this is because they dictate the sensors and commands right now - if self.sim.has_gui() and self.cfg.ui_window_class_type is not None: + if self.sim.carb_settings.get("/isaaclab/has_gui") and self.cfg.ui_window_class_type is not None: self._window = self.cfg.ui_window_class_type(self, window_name="IsaacLab") else: # if no window, then we don't need to store the window @@ -375,7 +375,7 @@ def step(self, actions: dict[AgentID, ActionType]) -> EnvStepReturn: # check if we need to do rendering within the physics loop # note: checked here once to avoid multiple checks within the loop - is_rendering = self.sim.has_gui() or self.sim.has_rtx_sensors() + is_rendering = self.sim.carb_settings.get("/isaaclab/has_gui") or self.sim.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") # perform physics stepping for _ in range(self.cfg.decimation): @@ -493,18 +493,16 @@ def render(self, recompute: bool = False) -> np.ndarray | None: """ # run a rendering step of the simulator # if we have rtx sensors, we do not need to render again sin - if not self.sim.has_rtx_sensors() and not recompute: + if not self.sim.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") and not recompute: self.sim.render() # decide the rendering mode if self.render_mode == "human" or self.render_mode is None: return None elif self.render_mode == "rgb_array": # check that if any render could have happened - if self.sim.render_mode.value < self.sim.RenderMode.PARTIAL_RENDERING.value: + if not self.sim.carb_settings.get("/isaaclab/has_gui") and not bool(self.sim.carb_settings.get("/isaaclab/render/offscreen")): raise RuntimeError( - f"Cannot render '{self.render_mode}' when the simulation render mode is" - f" '{self.sim.render_mode.name}'. Please set the simulation render mode to:" - f"'{self.sim.RenderMode.PARTIAL_RENDERING.name}' or '{self.sim.RenderMode.FULL_RENDERING.name}'." + f"Cannot render '{self.render_mode}' - no GUI and offscreen rendering not enabled." " If running headless, make sure --enable_cameras is set." ) # create the annotator if it does not exist @@ -550,9 +548,7 @@ def close(self): # detach physx stage omni.physx.get_physx_simulation_interface().detach_stage() self.sim.stop() - self.sim.clear() - self.sim.clear_all_callbacks() self.sim.clear_instance() # destroy the window diff --git a/source/isaaclab/isaaclab/envs/direct_rl_env.py b/source/isaaclab/isaaclab/envs/direct_rl_env.py index 69be0edb78d..94f86ba9093 100644 --- a/source/isaaclab/isaaclab/envs/direct_rl_env.py +++ b/source/isaaclab/isaaclab/envs/direct_rl_env.py @@ -22,7 +22,6 @@ import omni.kit.app import omni.physx -from isaacsim.core.simulation_manager import SimulationManager from isaaclab.managers import EventManager from isaaclab.scene import InteractiveScene @@ -130,7 +129,7 @@ def __init__(self, cfg: DirectRLEnvCfg, render_mode: str | None = None, **kwargs # generate scene with Timer("[INFO]: Time taken for scene creation", "scene_creation"): # set the stage context for scene creation steps which use the stage - with use_stage(self.sim.get_initial_stage()): + with use_stage(self.sim.stage): self.scene = InteractiveScene(self.cfg.scene) self._setup_scene() attach_stage_to_usd_context() @@ -140,7 +139,7 @@ def __init__(self, cfg: DirectRLEnvCfg, render_mode: str | None = None, **kwargs # viewport is not available in other rendering modes so the function will throw a warning # FIXME: This needs to be fixed in the future when we unify the UI functionalities even for # non-rendering modes. - if self.sim.render_mode >= self.sim.RenderMode.PARTIAL_RENDERING: + if self.sim.carb_settings.get("/isaaclab/has_gui"): self.viewport_camera_controller = ViewportCameraController(self, self.cfg.viewer) else: self.viewport_camera_controller = None @@ -163,7 +162,7 @@ def __init__(self, cfg: DirectRLEnvCfg, render_mode: str | None = None, **kwargs with Timer("[INFO]: Time taken for simulation start", "simulation_start"): # since the reset can trigger callbacks which use the stage, # we need to set the stage context here - with use_stage(self.sim.get_initial_stage()): + with use_stage(self.sim.stage): self.sim.reset() # update scene to pre populate data buffers for assets and sensors. # this is needed for the observation manager to get valid tensors for initialization. @@ -179,7 +178,7 @@ def __init__(self, cfg: DirectRLEnvCfg, render_mode: str | None = None, **kwargs # extend UI elements # we need to do this here after all the managers are initialized # this is because they dictate the sensors and commands right now - if self.sim.has_gui() and self.cfg.ui_window_class_type is not None: + if self.sim.carb_settings.get("/isaaclab/has_gui") and self.cfg.ui_window_class_type is not None: self._window = self.cfg.ui_window_class_type(self, window_name="IsaacLab") else: # if no window, then we don't need to store the window @@ -260,7 +259,7 @@ def physics_dt(self) -> float: This is the lowest time-decimation at which the simulation is happening. """ - return self.cfg.sim.dt + return self.cfg.sim.physics_manager_cfg.dt @property def step_dt(self) -> float: @@ -268,7 +267,7 @@ def step_dt(self) -> float: This is the time-step at which the environment steps forward. """ - return self.cfg.sim.dt * self.cfg.decimation + return self.cfg.sim.physics_manager_cfg.dt * self.cfg.decimation @property def device(self): @@ -283,7 +282,7 @@ def max_episode_length_s(self) -> float: @property def max_episode_length(self): """The maximum episode length in steps adjusted from s.""" - return math.ceil(self.max_episode_length_s / (self.cfg.sim.dt * self.cfg.decimation)) + return math.ceil(self.max_episode_length_s / (self.cfg.sim.physics_manager_cfg.dt * self.cfg.decimation)) """ Operations. @@ -319,13 +318,16 @@ def reset(self, seed: int | None = None, options: dict[str, Any] | None = None) self.sim.forward() # if sensors are added to the scene, make sure we render to reflect changes in reset - if self.sim.has_rtx_sensors() and self.cfg.num_rerenders_on_reset > 0: + if self.sim.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") and self.cfg.num_rerenders_on_reset > 0: for _ in range(self.cfg.num_rerenders_on_reset): self.sim.render() - if self.cfg.wait_for_textures and self.sim.has_rtx_sensors(): - while SimulationManager.assets_loading(): - self.sim.render() + if self.cfg.wait_for_textures and self.sim.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors"): + # Wait for assets to finish loading (PhysX-specific) + pm = self.sim.physics_manager + if hasattr(pm, "assets_loading"): + while pm.assets_loading(): + self.sim.render() # return observations return self._get_observations(), self.extras @@ -364,7 +366,7 @@ def step(self, action: torch.Tensor) -> VecEnvStepReturn: # check if we need to do rendering within the physics loop # note: checked here once to avoid multiple checks within the loop - is_rendering = self.sim.has_gui() or self.sim.has_rtx_sensors() + is_rendering = self.sim.carb_settings.get("/isaaclab/has_gui") or self.sim.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") # perform physics stepping for _ in range(self.cfg.decimation): @@ -397,7 +399,7 @@ def step(self, action: torch.Tensor) -> VecEnvStepReturn: if len(reset_env_ids) > 0: self._reset_idx(reset_env_ids) # if sensors are added to the scene, make sure we render to reflect changes in reset - if self.sim.has_rtx_sensors() and self.cfg.num_rerenders_on_reset > 0: + if self.sim.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") and self.cfg.num_rerenders_on_reset > 0: for _ in range(self.cfg.num_rerenders_on_reset): self.sim.render() @@ -461,18 +463,16 @@ def render(self, recompute: bool = False) -> np.ndarray | None: """ # run a rendering step of the simulator # if we have rtx sensors, we do not need to render again sin - if not self.sim.has_rtx_sensors() and not recompute: + if not self.sim.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") and not recompute: self.sim.render() # decide the rendering mode if self.render_mode == "human" or self.render_mode is None: return None elif self.render_mode == "rgb_array": # check that if any render could have happened - if self.sim.render_mode.value < self.sim.RenderMode.PARTIAL_RENDERING.value: + if not self.sim.carb_settings.get("/isaaclab/has_gui") and not bool(self.sim.carb_settings.get("/isaaclab/render/offscreen")): raise RuntimeError( - f"Cannot render '{self.render_mode}' when the simulation render mode is" - f" '{self.sim.render_mode.name}'. Please set the simulation render mode to:" - f"'{self.sim.RenderMode.PARTIAL_RENDERING.name}' or '{self.sim.RenderMode.FULL_RENDERING.name}'." + f"Cannot render '{self.render_mode}' - no GUI and offscreen rendering not enabled." " If running headless, make sure --enable_cameras is set." ) # create the annotator if it does not exist @@ -518,9 +518,7 @@ def close(self): # detach physx stage omni.physx.get_physx_simulation_interface().detach_stage() self.sim.stop() - self.sim.clear() - self.sim.clear_all_callbacks() self.sim.clear_instance() # destroy the window diff --git a/source/isaaclab/isaaclab/envs/manager_based_env.py b/source/isaaclab/isaaclab/envs/manager_based_env.py index 3ff6d291c0a..60718b46f44 100644 --- a/source/isaaclab/isaaclab/envs/manager_based_env.py +++ b/source/isaaclab/isaaclab/envs/manager_based_env.py @@ -12,7 +12,6 @@ import torch import omni.physx -from isaacsim.core.simulation_manager import SimulationManager from isaaclab.managers import ActionManager, EventManager, ObservationManager, RecorderManager from isaaclab.scene import InteractiveScene @@ -138,7 +137,7 @@ def __init__(self, cfg: ManagerBasedEnvCfg): # generate scene with Timer("[INFO]: Time taken for scene creation", "scene_creation"): # set the stage context for scene creation steps which use the stage - with use_stage(self.sim.get_initial_stage()): + with use_stage(self.sim.stage): self.scene = InteractiveScene(self.cfg.scene) attach_stage_to_usd_context() print("[INFO]: Scene manager: ", self.scene) @@ -147,7 +146,7 @@ def __init__(self, cfg: ManagerBasedEnvCfg): # viewport is not available in other rendering modes so the function will throw a warning # FIXME: This needs to be fixed in the future when we unify the UI functionalities even for # non-rendering modes. - if self.sim.render_mode >= self.sim.RenderMode.PARTIAL_RENDERING: + if self.sim.carb_settings.get("/isaaclab/has_gui"): self.viewport_camera_controller = ViewportCameraController(self, self.cfg.viewer) else: self.viewport_camera_controller = None @@ -169,7 +168,7 @@ def __init__(self, cfg: ManagerBasedEnvCfg): with Timer("[INFO]: Time taken for simulation start", "simulation_start"): # since the reset can trigger callbacks which use the stage, # we need to set the stage context here - with use_stage(self.sim.get_initial_stage()): + with use_stage(self.sim.stage): self.sim.reset() # update scene to pre populate data buffers for assets and sensors. # this is needed for the observation manager to get valid tensors for initialization. @@ -182,7 +181,7 @@ def __init__(self, cfg: ManagerBasedEnvCfg): # extend UI elements # we need to do this here after all the managers are initialized # this is because they dictate the sensors and commands right now - if self.sim.has_gui() and self.cfg.ui_window_class_type is not None: + if self.sim.carb_settings.get("/isaaclab/has_gui") and self.cfg.ui_window_class_type is not None: # setup live visualizers self.setup_manager_visualizers() self._window = self.cfg.ui_window_class_type(self, window_name="IsaacLab") @@ -230,7 +229,7 @@ def physics_dt(self) -> float: This is the lowest time-decimation at which the simulation is happening. """ - return self.cfg.sim.dt + return self.cfg.sim.physics_manager_cfg.dt @property def step_dt(self) -> float: @@ -238,7 +237,7 @@ def step_dt(self) -> float: This is the time-step at which the environment steps forward. """ - return self.cfg.sim.dt * self.cfg.decimation + return self.cfg.sim.physics_manager_cfg.dt * self.cfg.decimation @property def device(self): @@ -375,7 +374,7 @@ def reset( self.scene.write_data_to_sim() self.sim.forward() # if sensors are added to the scene, make sure we render to reflect changes in reset - if self.sim.has_rtx_sensors() and self.cfg.num_rerenders_on_reset > 0: + if self.sim.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") and self.cfg.num_rerenders_on_reset > 0: for _ in range(self.cfg.num_rerenders_on_reset): self.sim.render() @@ -385,9 +384,12 @@ def reset( # compute observations self.obs_buf = self.observation_manager.compute(update_history=True) - if self.cfg.wait_for_textures and self.sim.has_rtx_sensors(): - while SimulationManager.assets_loading(): - self.sim.render() + if self.cfg.wait_for_textures and self.sim.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors"): + # Wait for assets to finish loading (PhysX-specific) + pm = self.sim.physics_manager + if hasattr(pm, "assets_loading"): + while pm.assets_loading(): + self.sim.render() # return observations return self.obs_buf, self.extras @@ -436,7 +438,7 @@ def reset_to( self.sim.forward() # if sensors are added to the scene, make sure we render to reflect changes in reset - if self.sim.has_rtx_sensors() and self.cfg.num_rerenders_on_reset > 0: + if self.sim.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") and self.cfg.num_rerenders_on_reset > 0: for _ in range(self.cfg.num_rerenders_on_reset): self.sim.render() @@ -471,7 +473,7 @@ def step(self, action: torch.Tensor) -> tuple[VecEnvObs, dict]: # check if we need to do rendering within the physics loop # note: checked here once to avoid multiple checks within the loop - is_rendering = self.sim.has_gui() or self.sim.has_rtx_sensors() + is_rendering = self.sim.carb_settings.get("/isaaclab/has_gui") or self.sim.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") # perform physics stepping for _ in range(self.cfg.decimation): @@ -538,9 +540,7 @@ def close(self): # detach physx stage omni.physx.get_physx_simulation_interface().detach_stage() self.sim.stop() - self.sim.clear() - self.sim.clear_all_callbacks() self.sim.clear_instance() # destroy the window diff --git a/source/isaaclab/isaaclab/envs/manager_based_rl_env.py b/source/isaaclab/isaaclab/envs/manager_based_rl_env.py index ab8c04155d2..efd93f53637 100644 --- a/source/isaaclab/isaaclab/envs/manager_based_rl_env.py +++ b/source/isaaclab/isaaclab/envs/manager_based_rl_env.py @@ -176,7 +176,7 @@ def step(self, action: torch.Tensor) -> VecEnvStepReturn: # check if we need to do rendering within the physics loop # note: checked here once to avoid multiple checks within the loop - is_rendering = self.sim.has_gui() or self.sim.has_rtx_sensors() + is_rendering = self.sim.carb_settings.get("/isaaclab/has_gui") or self.sim.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") # perform physics stepping for _ in range(self.cfg.decimation): @@ -221,7 +221,7 @@ def step(self, action: torch.Tensor) -> VecEnvStepReturn: self._reset_idx(reset_env_ids) # if sensors are added to the scene, make sure we render to reflect changes in reset - if self.sim.has_rtx_sensors() and self.cfg.num_rerenders_on_reset > 0: + if self.sim.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") and self.cfg.num_rerenders_on_reset > 0: for _ in range(self.cfg.num_rerenders_on_reset): self.sim.render() @@ -264,18 +264,16 @@ def render(self, recompute: bool = False) -> np.ndarray | None: """ # run a rendering step of the simulator # if we have rtx sensors, we do not need to render again sin - if not self.sim.has_rtx_sensors() and not recompute: + if not self.sim.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") and not recompute: self.sim.render() # decide the rendering mode if self.render_mode == "human" or self.render_mode is None: return None elif self.render_mode == "rgb_array": # check that if any render could have happened - if self.sim.render_mode.value < self.sim.RenderMode.PARTIAL_RENDERING.value: + if not self.sim.carb_settings.get("/isaaclab/has_gui") and not bool(self.sim.carb_settings.get("/isaaclab/render/offscreen")): raise RuntimeError( - f"Cannot render '{self.render_mode}' when the simulation render mode is" - f" '{self.sim.render_mode.name}'. Please set the simulation render mode to:" - f"'{self.sim.RenderMode.PARTIAL_RENDERING.name}' or '{self.sim.RenderMode.FULL_RENDERING.name}'." + f"Cannot render '{self.render_mode}' - no GUI and offscreen rendering not enabled." " If running headless, make sure --enable_cameras is set." ) # create the annotator if it does not exist diff --git a/source/isaaclab/isaaclab/envs/ui/base_env_window.py b/source/isaaclab/isaaclab/envs/ui/base_env_window.py index 2aafe5e6bba..a0760f9b011 100644 --- a/source/isaaclab/isaaclab/envs/ui/base_env_window.py +++ b/source/isaaclab/isaaclab/envs/ui/base_env_window.py @@ -123,18 +123,8 @@ def _build_sim_frame(self): # create stack for controls self.ui_window_elements["sim_vstack"] = omni.ui.VStack(spacing=5, height=0) with self.ui_window_elements["sim_vstack"]: - # create rendering mode dropdown - render_mode_cfg = { - "label": "Rendering Mode", - "type": "dropdown", - "default_val": self.env.sim.render_mode.value, - "items": [member.name for member in self.env.sim.RenderMode if member.value >= 0], - "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( - **render_mode_cfg - ) + # Note: Rendering mode dropdown removed - rendering is now managed through visualizer config + pass # create animation recording box record_animate_cfg = { diff --git a/source/isaaclab/isaaclab/physics/__init__.py b/source/isaaclab/isaaclab/physics/__init__.py new file mode 100644 index 00000000000..d61c06d65a3 --- /dev/null +++ b/source/isaaclab/isaaclab/physics/__init__.py @@ -0,0 +1,16 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Implementation backends for simulation interfaces.""" + +from .physics_manager import PhysicsManager, PhysicsEvent, CallbackHandle +from .physics_manager_cfg import PhysicsManagerCfg + +__all__ = [ + "PhysicsManager", + "PhysicsEvent", + "CallbackHandle", + "PhysicsManagerCfg", +] diff --git a/source/isaaclab/isaaclab/physics/physics_manager.py b/source/isaaclab/isaaclab/physics/physics_manager.py new file mode 100644 index 00000000000..df4148caa3b --- /dev/null +++ b/source/isaaclab/isaaclab/physics/physics_manager.py @@ -0,0 +1,335 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Base class for physics managers with unified callback system.""" + +from __future__ import annotations + +import logging +import weakref +from abc import ABC, abstractmethod +from enum import Enum +from typing import TYPE_CHECKING, Any, Callable, ClassVar + +if TYPE_CHECKING: + from isaaclab.sim.simulation_context import SimulationContext + +logger = logging.getLogger(__name__) + + +class PhysicsEvent(Enum): + """Physics simulation lifecycle events. + + These are general events that apply across all physics backends. + Backend-specific events (e.g., PhysX timeline events) are handled + by the respective manager classes. + + Lifecycle order: MODEL_INIT -> PHYSICS_READY -> (PRE_STEP -> POST_STEP)* -> STOP + """ + + MODEL_INIT = "model_init" + """Physics model is being constructed. + Fired during scene building, before simulation can run. Use this to register + physics representations (rigid bodies, joints, constraints) with the solver. + """ + + PHYSICS_READY = "physics_ready" + """Physics is initialized and queryable. + Fired after all physics data structures are created and the simulation is + ready to step. Assets can now read initial state (positions, velocities). + """ + + PRE_STEP = "pre_step" + """About to advance physics by one timestep.""" + + POST_STEP = "post_step" + """Called after each physics step.""" + + STOP = "stop" + """Simulation is stopping.""" + + +class CallbackHandle: + """Handle for a registered callback, allowing deregistration.""" + + def __init__(self, callback_id: int, manager: type["PhysicsManager"]): + self._id = callback_id + self._manager = manager + + @property + def id(self) -> int: + return self._id + + def deregister(self) -> None: + """Remove this callback from the manager.""" + self._manager.deregister_callback(self._id) + + +class PhysicsManager(ABC): + """Abstract base class for physics simulation managers. + + Physics managers handle the lifecycle of a physics simulation backend, + including initialization, stepping, and cleanup. + + This base class provides: + - Unified callback management system + - Common state variables (_sim, _cfg, _device) + - Default accessor implementations + + Lifecycle: initialize() -> reset() -> step() (repeated) -> close() + """ + + _sim: ClassVar["SimulationContext | None"] = None + _cfg: ClassVar[Any] = None + _device: ClassVar[str] = "cuda:0" + _sim_time: ClassVar[float] = 0.0 + _callbacks: ClassVar[dict[int, tuple[Any, Callable, int, str | None, Any]]] = {} + _callback_id: ClassVar[int] = 0 + + @classmethod + def register_callback( + cls, + callback: Callable[[Any], None], + event: PhysicsEvent, + order: int = 0, + name: str | None = None, + wrap_weak_ref: bool = True, + ) -> CallbackHandle: + """Register a callback for a physics event. + + Args: + callback: The callback function. Receives event payload as argument. + event: The event to listen for. + order: Priority order (lower = earlier). Default 0. + name: Optional name for debugging. + wrap_weak_ref: If True, wrap bound methods with weak references + to prevent preventing garbage collection. Default True. + + Returns: + CallbackHandle that can be used to deregister the callback. + + Example: + >>> def on_physics_ready(payload): + ... print("Physics is ready!") + >>> handle = PhysxManager.register_callback( + ... on_physics_ready, + ... PhysicsEvent.PHYSICS_READY + ... ) + >>> # Later, to remove: + >>> handle.deregister() + """ + cid = cls._callback_id + cls._callback_id += 1 + + if wrap_weak_ref: + callback = cls._wrap_weak_ref(callback) + + subscription = cls._subscribe_to_event(cid, callback, event, order, name) + + cls._callbacks[cid] = (event, callback, order, name, subscription) + return CallbackHandle(cid, cls) + + @classmethod + def deregister_callback(cls, callback_id: int | CallbackHandle) -> None: + """Remove a registered callback. + + Args: + callback_id: The ID or CallbackHandle returned by register_callback(). + """ + cid = callback_id.id if isinstance(callback_id, CallbackHandle) else callback_id + if cid not in cls._callbacks: + return + + event, callback, order, name, subscription = cls._callbacks.pop(cid) + cls._unsubscribe_from_event(cid, event, subscription) + + @classmethod + def dispatch_event(cls, event: PhysicsEvent, payload: Any = None) -> None: + """Dispatch an event to all registered callbacks. + + This is the default implementation using simple callback lists. + Subclasses may override or extend with platform-specific dispatch. + + Args: + event: The event to dispatch. + payload: Optional data to pass to callbacks. + """ + matching = [ + (cid, cb, order) + for cid, (ev, cb, order, name, sub) in cls._callbacks.items() + if ev == event + ] + matching.sort(key=lambda x: x[2]) + + for cid, callback, order in matching: + try: + callback(payload) + except ReferenceError: + cls.deregister_callback(cid) + except Exception as e: + logger.error(f"Callback {cid} for {event.value} failed: {e}") + + @classmethod + def clear_callbacks(cls) -> None: + """Remove all registered callbacks.""" + for cid in list(cls._callbacks.keys()): + cls.deregister_callback(cid) + cls._callbacks.clear() + cls._callback_id = 0 + + @classmethod + def _wrap_weak_ref(cls, callback: Callable) -> Callable: + """Wrap bound methods with weak references to prevent leaks. + + Args: + callback: The callback to wrap. + + Returns: + Wrapped callback if it's a bound method, otherwise original. + """ + if hasattr(callback, "__self__"): + obj_ref = weakref.proxy(callback.__self__) + method_name = callback.__name__ + + def weak_callback(payload: Any) -> Any: + return getattr(obj_ref, method_name)(payload) + + return weak_callback + return callback + + @classmethod + def _subscribe_to_event( + cls, + callback_id: int, + callback: Callable, + event: PhysicsEvent, + order: int, + name: str | None, + ) -> Any: + """Subscribe to a platform-specific event. + + Override in subclasses to integrate with platform event systems + (e.g., Omniverse event bus, timeline events). + + Args: + callback_id: Unique ID for this callback. + callback: The callback function. + event: The event to subscribe to. + order: Priority order. + name: Optional name. + + Returns: + Platform-specific subscription object (stored for cleanup). + """ + return None + + @classmethod + def _unsubscribe_from_event( + cls, + callback_id: int, + event: PhysicsEvent, + subscription: Any, + ) -> None: + """Unsubscribe from a platform-specific event. + + Override in subclasses to clean up platform subscriptions. + + Args: + callback_id: The callback ID being removed. + event: The event that was subscribed to. + subscription: The subscription object from _subscribe_to_event(). + """ + pass + + @classmethod + @abstractmethod + def initialize(cls, sim_context: "SimulationContext") -> None: + """Initialize the physics manager with simulation context. + + Subclasses should call super().initialize() first, then do backend-specific setup. + + Args: + sim_context: Parent simulation context. + """ + # Set on PhysicsManager explicitly so PhysicsManager.get_*() works + # regardless of which subclass is active (Python class vars are per-class) + PhysicsManager._sim = sim_context + PhysicsManager._cfg = sim_context.cfg.physics_manager_cfg + PhysicsManager._sim_time = 0.0 + + @classmethod + @abstractmethod + def reset(cls, soft: bool = False) -> None: + """Reset physics simulation. + + Args: + soft: If True, skip full reinitialization. + """ + pass + + @classmethod + @abstractmethod + def forward(cls) -> None: + """Update kinematics without stepping physics (for rendering).""" + pass + + @classmethod + @abstractmethod + def step(cls) -> None: + """Step physics simulation by one timestep (physics only, no rendering).""" + pass + + @classmethod + def close(cls) -> None: + """Clean up physics resources. + + Subclasses should call super().close() after backend-specific cleanup. + """ + cls.dispatch_event(PhysicsEvent.STOP) # notify listeners before cleanup + cls.clear_callbacks() + # Reset on PhysicsManager explicitly (matches initialize()) + PhysicsManager._sim = None + PhysicsManager._cfg = None + PhysicsManager._sim_time = 0.0 + + @classmethod + def get_physics_dt(cls) -> float: + """Get the physics timestep in seconds.""" + return PhysicsManager._cfg.dt if PhysicsManager._cfg else 1.0 / 60.0 + + @classmethod + def get_device(cls) -> str: + """Get the physics simulation device.""" + return PhysicsManager._device + + @classmethod + def get_simulation_time(cls) -> float: + """Get the current simulation time in seconds.""" + return PhysicsManager._sim_time + + @classmethod + def get_physics_sim_view(cls) -> Any: + """Get the physics simulation view. Override in subclasses.""" + return None + + @classmethod + def play(cls) -> None: + """Start or resume physics simulation. Default is no-op.""" + pass + + @classmethod + def pause(cls) -> None: + """Pause physics simulation. Default is no-op.""" + pass + + @classmethod + def stop(cls) -> None: + """Stop physics simulation. Default is no-op.""" + pass + + @classmethod + def get_backend(cls) -> str: + """Get the tensor backend being used ("numpy" or "torch").""" + return "torch" if "cuda" in PhysicsManager._device else "numpy" diff --git a/source/isaaclab/isaaclab/physics/physics_manager_cfg.py b/source/isaaclab/isaaclab/physics/physics_manager_cfg.py new file mode 100644 index 00000000000..2f38eb703e6 --- /dev/null +++ b/source/isaaclab/isaaclab/physics/physics_manager_cfg.py @@ -0,0 +1,62 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Base configuration for physics managers.""" + +from __future__ import annotations + +from typing import TYPE_CHECKING + +from dataclasses import MISSING + +from isaaclab.utils import configclass +from isaaclab.sim.spawners.materials import RigidBodyMaterialCfg + +if TYPE_CHECKING: + from .physics_manager import PhysicsManager + + +@configclass +class PhysicsManagerCfg: + """Abstract base configuration for physics managers. + + This base class contains common simulation parameters shared across + all physics backends. Subclasses should override :meth:`create_manager` + to return the appropriate physics manager class. + """ + + # ------------------------------------------------------------------ + # Common Simulation Parameters + # ------------------------------------------------------------------ + + class_type: type[PhysicsManager] = MISSING + + dt: float = 1.0 / 60.0 + """The physics simulation time-step (in seconds). Default is 0.0167 seconds.""" + + device: str = "cuda:0" + """The device to run the simulation on. Default is ``"cuda:0"``. + + Valid options are: + + - ``"cpu"``: Use CPU. + - ``"cuda"``: Use GPU, where the device ID is inferred from config. + - ``"cuda:N"``: Use GPU, where N is the device ID. For example, "cuda:0". + """ + + gravity: tuple[float, float, float] = (0.0, 0.0, -9.81) + """The gravity vector (in m/s^2). Default is (0.0, 0.0, -9.81).""" + + physics_prim_path: str = "/physicsScene" + """The prim path where the USD PhysicsScene is created. Default is "/physicsScene".""" + + physics_material: RigidBodyMaterialCfg = RigidBodyMaterialCfg() + """Default physics material settings for rigid bodies. Default is None (uses RigidBodyMaterialCfg defaults). + + The physics engine defaults to this physics material for all the rigid body prims that do not have any + physics material specified on them. + + The material is created at the path: ``{physics_prim_path}/defaultMaterial``. + """ diff --git a/source/isaaclab/isaaclab/sensors/ray_caster/ray_caster.py b/source/isaaclab/isaaclab/sensors/ray_caster/ray_caster.py index e6735a9f481..469dd40a991 100644 --- a/source/isaaclab/isaaclab/sensors/ray_caster/ray_caster.py +++ b/source/isaaclab/isaaclab/sensors/ray_caster/ray_caster.py @@ -15,10 +15,10 @@ import warp as wp import omni -from isaacsim.core.simulation_manager import SimulationManager from pxr import UsdGeom, UsdPhysics import isaaclab.sim as sim_utils +from isaaclab.physics import PhysicsManager import isaaclab.utils.math as math_utils from isaaclab.markers import VisualizationMarkers from isaaclab.sim.views import XformPrimView @@ -144,7 +144,7 @@ def _initialize_impl(self): super()._initialize_impl() # obtain global simulation view - self._physics_sim_view = SimulationManager.get_physics_sim_view() + self._physics_sim_view = PhysicsManager.get_physics_sim_view() prim = sim_utils.find_first_matching_prim(self.cfg.prim_path) if prim is None: available_prims = ",".join([str(p.GetPath()) for p in sim_utils.get_current_stage().Traverse()]) diff --git a/source/isaaclab/isaaclab/sensors/sensor_base.py b/source/isaaclab/isaaclab/sensors/sensor_base.py index 59c8581463b..df4102be48c 100644 --- a/source/isaaclab/isaaclab/sensors/sensor_base.py +++ b/source/isaaclab/isaaclab/sensors/sensor_base.py @@ -11,7 +11,6 @@ from __future__ import annotations -import builtins import inspect import re import weakref @@ -22,10 +21,10 @@ import torch import omni.kit.app -import omni.timeline -from isaacsim.core.simulation_manager import IsaacEvents, SimulationManager import isaaclab.sim as sim_utils +from isaaclab.physics import PhysicsEvent, PhysicsManager +from isaaclab_physx.physics import IsaacEvents, PhysxManager from isaaclab.sim.utils.stage import get_current_stage if TYPE_CHECKING: @@ -255,7 +254,7 @@ def _debug_vis_callback(self, event): """ def _register_callbacks(self): - """Registers the timeline and prim deletion callbacks.""" + """Registers physics lifecycle and prim deletion callbacks.""" # register simulator callbacks (with weakref safety to avoid crashes on deletion) def safe_callback(callback_name, event, obj_ref): @@ -268,27 +267,24 @@ def safe_callback(callback_name, event, obj_ref): pass # note: use weakref on callbacks to ensure that this object can be deleted when its destructor is called. - # add callbacks for stage play/stop obj_ref = weakref.proxy(self) - timeline_event_stream = omni.timeline.get_timeline_interface().get_timeline_event_stream() - # the order is set to 10 which is arbitrary but should be lower priority than the default order of 0 - # register timeline PLAY event callback (lower priority with order=10) - self._initialize_handle = timeline_event_stream.create_subscription_to_pop_by_type( - int(omni.timeline.TimelineEventType.PLAY), - lambda event, obj_ref=obj_ref: safe_callback("_initialize_callback", event, obj_ref), + # Register PHYSICS_READY callback for initialization (order=10 for lower priority) + self._initialize_handle = PhysxManager.register_callback( + lambda payload, obj_ref=obj_ref: safe_callback("_initialize_callback", payload, obj_ref), + PhysicsEvent.PHYSICS_READY, order=10, ) - # register timeline STOP event callback (lower priority with order=10) - self._invalidate_initialize_handle = timeline_event_stream.create_subscription_to_pop_by_type( - int(omni.timeline.TimelineEventType.STOP), + # Register TIMELINE_STOP callback for invalidation (PhysX-specific) + self._invalidate_initialize_handle = PhysxManager.register_callback( lambda event, obj_ref=obj_ref: safe_callback("_invalidate_initialize_callback", event, obj_ref), + IsaacEvents.TIMELINE_STOP, order=10, ) - # register prim deletion callback - self._prim_deletion_callback_id = SimulationManager.register_callback( + # Register PRIM_DELETION callback (PhysX-specific) + self._prim_deletion_handle = PhysxManager.register_callback( lambda event, obj_ref=obj_ref: safe_callback("_on_prim_deletion", event, obj_ref), - event=IsaacEvents.PRIM_DELETION, + IsaacEvents.PRIM_DELETION, ) def _initialize_callback(self, event): @@ -302,8 +298,8 @@ def _initialize_callback(self, event): try: self._initialize_impl() except Exception as e: - if builtins.ISAACLAB_CALLBACK_EXCEPTION is None: - builtins.ISAACLAB_CALLBACK_EXCEPTION = e + # Store exception to be raised after callback completes + PhysxManager.store_callback_exception(e) self._is_initialized = True def _invalidate_initialize_callback(self, event): @@ -313,15 +309,16 @@ def _invalidate_initialize_callback(self, event): self._debug_vis_handle.unsubscribe() self._debug_vis_handle = None - def _on_prim_deletion(self, prim_path: str) -> None: + def _on_prim_deletion(self, event) -> None: """Invalidates and deletes the callbacks when the prim is deleted. Args: - prim_path: The path to the prim that is being deleted. + event: The prim deletion event containing the prim path in payload. - .. note:: + Note: This function is called when the prim is deleted. """ + prim_path = event.payload["prim_path"] if prim_path == "/": self._clear_callbacks() return @@ -333,17 +330,17 @@ 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) - self._prim_deletion_callback_id = None - if self._initialize_handle: - self._initialize_handle.unsubscribe() + if self._initialize_handle is not None: + self._initialize_handle.deregister() self._initialize_handle = None - if self._invalidate_initialize_handle: - self._invalidate_initialize_handle.unsubscribe() + if self._invalidate_initialize_handle is not None: + self._invalidate_initialize_handle.deregister() self._invalidate_initialize_handle = None - # clear debug visualization - if self._debug_vis_handle: + if self._prim_deletion_handle is not None: + self._prim_deletion_handle.deregister() + self._prim_deletion_handle = None + # Clear debug visualization + if self._debug_vis_handle is not None: self._debug_vis_handle.unsubscribe() self._debug_vis_handle = None diff --git a/source/isaaclab/isaaclab/sim/__init__.py b/source/isaaclab/isaaclab/sim/__init__.py index 1dc920f4e10..ea3b3c7c82e 100644 --- a/source/isaaclab/isaaclab/sim/__init__.py +++ b/source/isaaclab/isaaclab/sim/__init__.py @@ -28,7 +28,7 @@ from .converters import * # noqa: F401, F403 from .schemas import * # noqa: F401, F403 -from .simulation_cfg import PhysxCfg, RenderCfg, SimulationCfg # noqa: F401, F403 +from .simulation_cfg import RenderCfg, SimulationCfg # noqa: F401, F403 from .simulation_context import SimulationContext, build_simulation_context # noqa: F401, F403 from .spawners import * # noqa: F401, F403 from .utils import * # noqa: F401, F403 diff --git a/source/isaaclab/isaaclab/sim/simulation_cfg.py b/source/isaaclab/isaaclab/sim/simulation_cfg.py index c0d80b49de6..ca6bb8f9078 100644 --- a/source/isaaclab/isaaclab/sim/simulation_cfg.py +++ b/source/isaaclab/isaaclab/sim/simulation_cfg.py @@ -9,190 +9,13 @@ configuring the environment instances, viewer settings, and simulation parameters. """ -from typing import Any, Literal +from typing import Any, Literal # Literal used by RenderCfg from isaaclab.utils import configclass -from .spawners.materials import RigidBodyMaterialCfg - - -@configclass -class PhysxCfg: - """Configuration for PhysX solver-related parameters. - - These parameters are used to configure the PhysX solver. For more information, see the `PhysX 5 SDK - documentation`_. - - PhysX 5 supports GPU-accelerated physics simulation. This is enabled by default, but can be disabled - by setting the :attr:`~SimulationCfg.device` to ``cpu`` in :class:`SimulationCfg`. Unlike CPU PhysX, the GPU - simulation feature is unable to dynamically grow all the buffers. Therefore, it is necessary to provide - a reasonable estimate of the buffer sizes for GPU features. If insufficient buffer sizes are provided, the - simulation will fail with errors and lead to adverse behaviors. The buffer sizes can be adjusted through the - ``gpu_*`` parameters. - - .. _PhysX 5 SDK documentation: https://nvidia-omniverse.github.io/PhysX/physx/5.4.1/_api_build/classPxSceneDesc.html - - """ - - solver_type: Literal[0, 1] = 1 - """The type of solver to use.Default is 1 (TGS). - - Available solvers: - - * :obj:`0`: PGS (Projective Gauss-Seidel) - * :obj:`1`: TGS (Temporal Gauss-Seidel) - """ - - solve_articulation_contact_last: bool = False - """Changes the ordering inside the articulation solver. Default is False. - - PhysX employs a strict ordering for handling constraints in an articulation. The outcome of - each constraint resolution modifies the joint and associated link speeds. However, the default - ordering may not be ideal for gripping scenarios because the solver favours the constraint - types that are resolved last. This is particularly true of stiff constraint systems that are hard - to resolve without resorting to vanishingly small simulation timesteps. - - With dynamic contact resolution being such an important part of gripping, it may make - more sense to solve dynamic contact towards the end of the solver rather than at the - beginning. This parameter modifies the default ordering to enable this change. - - For more information, please check `here `__. - - .. versionadded:: v2.3 - This parameter is only available with Isaac Sim 5.1. - - """ - - min_position_iteration_count: int = 1 - """Minimum number of solver position iterations (rigid bodies, cloth, particles etc.). Default is 1. - - .. note:: - - Each physics actor in Omniverse specifies its own solver iteration count. The solver takes - the number of iterations specified by the actor with the highest iteration and clamps it to - the range ``[min_position_iteration_count, max_position_iteration_count]``. - """ - - max_position_iteration_count: int = 255 - """Maximum number of solver position iterations (rigid bodies, cloth, particles etc.). Default is 255. - - .. note:: - - Each physics actor in Omniverse specifies its own solver iteration count. The solver takes - the number of iterations specified by the actor with the highest iteration and clamps it to - the range ``[min_position_iteration_count, max_position_iteration_count]``. - """ - - min_velocity_iteration_count: int = 0 - """Minimum number of solver velocity iterations (rigid bodies, cloth, particles etc.). Default is 0. - - .. note:: - - Each physics actor in Omniverse specifies its own solver iteration count. The solver takes - the number of iterations specified by the actor with the highest iteration and clamps it to - the range ``[min_velocity_iteration_count, max_velocity_iteration_count]``. - """ - - max_velocity_iteration_count: int = 255 - """Maximum number of solver velocity iterations (rigid bodies, cloth, particles etc.). Default is 255. - - .. note:: - - Each physics actor in Omniverse specifies its own solver iteration count. The solver takes - the number of iterations specified by the actor with the highest iteration and clamps it to - the range ``[min_velocity_iteration_count, max_velocity_iteration_count]``. - """ - - enable_ccd: bool = False - """Enable a second broad-phase pass that makes it possible to prevent objects from tunneling through each other. - Default is False.""" - - enable_stabilization: bool = False - """Enable/disable additional stabilization pass in solver. Default is False. - - .. note:: - - We recommend setting this flag to true only when the simulation step size is large - (i.e., less than 30 Hz or more than 0.0333 seconds). - - .. warning:: - - Enabling this flag may lead to incorrect contact forces report from the contact sensor. - """ - - enable_external_forces_every_iteration: bool = False - """Enable/disable external forces every position iteration in the TGS solver. Default is False. - - When using the TGS solver (:attr:`solver_type` is 1), this flag allows enabling external forces every solver - position iteration. This can help improve the accuracy of velocity updates. Consider enabling this flag if - the velocities generated by the simulation are noisy. Increasing the number of velocity iterations, together - with this flag, can help improve the accuracy of velocity updates. - - .. note:: - - This flag is ignored when using the PGS solver (:attr:`solver_type` is 0). - """ - - enable_enhanced_determinism: bool = False - """Enable/disable improved determinism at the expense of performance. Defaults to False. - - For more information on PhysX determinism, please check `here`_. - - .. _here: https://nvidia-omniverse.github.io/PhysX/physx/5.4.1/docs/RigidBodyDynamics.html#enhanced-determinism - """ - - bounce_threshold_velocity: float = 0.5 - """Relative velocity threshold for contacts to bounce (in m/s). Default is 0.5 m/s.""" - - friction_offset_threshold: float = 0.04 - """Threshold for contact point to experience friction force (in m). Default is 0.04 m.""" - - friction_correlation_distance: float = 0.025 - """Distance threshold for merging contacts into a single friction anchor point (in m). Default is 0.025 m.""" - - gpu_max_rigid_contact_count: int = 2**23 - """Size of rigid contact stream buffer allocated in pinned host memory. Default is 2 ** 23.""" - - gpu_max_rigid_patch_count: int = 5 * 2**15 - """Size of the rigid contact patch stream buffer allocated in pinned host memory. Default is 5 * 2 ** 15.""" - - gpu_found_lost_pairs_capacity: int = 2**21 - """Capacity of found and lost buffers allocated in GPU global memory. Default is 2 ** 21. - - This is used for the found/lost pair reports in the BP. - """ - - gpu_found_lost_aggregate_pairs_capacity: int = 2**25 - """Capacity of found and lost buffers in aggregate system allocated in GPU global memory. - Default is 2 ** 25. - - This is used for the found/lost pair reports in AABB manager. - """ - - gpu_total_aggregate_pairs_capacity: int = 2**21 - """Capacity of total number of aggregate pairs allocated in GPU global memory. Default is 2 ** 21.""" - - gpu_collision_stack_size: int = 2**26 - """Size of the collision stack buffer allocated in pinned host memory. Default is 2 ** 26.""" - - gpu_heap_capacity: int = 2**26 - """Initial capacity of the GPU and pinned host memory heaps. Additional memory will be allocated - if more memory is required. Default is 2 ** 26.""" - - gpu_temp_buffer_capacity: int = 2**24 - """Capacity of temp buffer allocated in pinned host memory. Default is 2 ** 24.""" - - gpu_max_num_partitions: int = 8 - """Limitation for the partitions in the GPU dynamics pipeline. Default is 8. - - This variable must be power of 2. A value greater than 32 is currently not supported. Range: (1, 32) - """ - - gpu_max_soft_body_contacts: int = 2**20 - """Size of soft body contacts stream buffer allocated in pinned host memory. Default is 2 ** 20.""" - - gpu_max_particle_contacts: int = 2**20 - """Size of particle contacts stream buffer allocated in pinned host memory. Default is 2 ** 20.""" +from isaaclab.physics.physics_manager_cfg import PhysicsManagerCfg +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab.visualizers import VisualizerCfg @configclass @@ -214,8 +37,7 @@ class RenderCfg: """ enable_translucency: bool | None = None - """Enables translucency for specular transmissive surfaces such as glass at the cost of some performance. - Default is False. + """Enables translucency for specular transmissive surfaces such as glass at the cost of some performance. Default is False. This is set by the variable: ``/rtx/translucency/enabled``. """ @@ -236,11 +58,10 @@ class RenderCfg: """Selects the anti-aliasing mode to use. Defaults to DLSS. - **DLSS**: Boosts performance by using AI to output higher resolution frames from a lower resolution input. - DLSS samples multiple lower resolution images and uses motion data and feedback from prior frames to - reconstruct native quality images. - - **DLAA**: Provides higher image quality with an AI-based anti-aliasing technique. DLAA uses the same - Super Resolution technology developed for DLSS, reconstructing a native resolution image to maximize - image quality. + DLSS samples multiple lower resolution images and uses motion data and feedback from prior frames to reconstruct + native quality images. + - **DLAA**: Provides higher image quality with an AI-based anti-aliasing technique. DLAA uses the same Super Resolution + technology developed for DLSS, reconstructing a native resolution image to maximize image quality. This is set by the variable: ``/rtx/post/dlss/execMode``. """ @@ -327,97 +148,12 @@ class RenderCfg: This is set by the variable: ``/rtx/domeLight/upperLowerStrategy``. """ - max_bounces: int | None = None - """Maximum number of ray bounces for path tracing (RT2). Default is 2. - - For global illumination (indirect diffuse), this should be at least 3. - - This is set by the variable: ``/rtx/rtpt/maxBounces``. - """ - - split_glass: bool | None = None - """Enables separate glass ray splitting for improved glass rendering (RT2). Default is False. - - Enabling this can reduce noise on glass materials at the cost of performance. - - This is set by the variable: ``/rtx/rtpt/splitGlass``. - """ - - split_clearcoat: bool | None = None - """Enables separate clearcoat ray splitting (RT2). Default is False. - - Enabling this can reduce noise on clearcoat materials at the cost of performance. - - This is set by the variable: ``/rtx/rtpt/splitClearcoat``. - """ - - split_rough_reflection: bool | None = None - """Enables separate rough reflection ray splitting (RT2). Default is False. - - Enabling this can reduce noise on rough reflective materials at the cost of performance. - - This is set by the variable: ``/rtx/rtpt/splitRoughReflection``. - """ - - ambient_light_intensity: float | None = None - """Scene ambient light intensity. Default is 1.0. - - This is set by the variable: ``/rtx/sceneDb/ambientLightIntensity``. - """ - - ambient_occlusion_denoiser_mode: Literal[0, 1] | None = None - """Ambient occlusion denoiser mode. Default is 1. - - Valid values are: - - * 0: Higher quality denoising - * 1: Performance-oriented denoising - - This is set by the variable: ``/rtx/ambientOcclusion/denoiserMode``. - """ - - subpixel_mode: Literal[0, 1] | None = None - """Raytracing subpixel mode. Default is 0. - - Valid values are: - - * 0: Performance mode - * 1: Quality mode (better anti-aliasing) - - This is set by the variable: ``/rtx/raytracing/subpixel/mode``. - """ - - enable_cached_raytracing: bool | None = None - """Enables cached raytracing for improved performance. Default is True. - - This is set by the variable: ``/rtx/raytracing/cached/enabled``. - """ - - max_samples_per_launch: int | None = None - """Maximum samples per launch for path tracing. Default is 1000000. - - This setting helps avoid replicator warnings when using large tile counts. - - This is set by the variable: ``/rtx/pathtracing/maxSamplesPerLaunch``. - """ - - view_tile_limit: int | None = None - """Maximum number of view tiles. Default is 1000000. - - This setting helps avoid silent trimming of tiles. - - This is set by the variable: ``/rtx/viewTile/limit``. - """ - carb_settings: dict[str, Any] | None = None """A general dictionary for users to supply all carb rendering settings with native names. The keys of the dictionary can be formatted like a carb setting, .kit file setting, or python variable. - For instance, a key value pair can be: - - - ``/rtx/translucency/enabled: False`` (carb) - - ``rtx.translucency.enabled: False`` (.kit) - - ``rtx_translucency_enabled: False`` (python) + For instance, a key value pair can be ``/rtx/translucency/enabled: False`` (carb), ``rtx.translucency.enabled: False`` (.kit), + or ``rtx_translucency_enabled: False`` (python). """ rendering_mode: Literal["performance", "balanced", "quality"] | None = None @@ -431,9 +167,6 @@ class RenderCfg: class SimulationCfg: """Configuration for simulation physics.""" - physics_prim_path: str = "/physicsScene" - """The prim path where the USD PhysicsScene is created. Default is "/physicsScene".""" - device: str = "cuda:0" """The device to run the simulation on. Default is ``"cuda:0"``. @@ -444,18 +177,9 @@ class SimulationCfg: - ``"cuda:N"``: Use GPU, where N is the device ID. For example, "cuda:0". """ - dt: float = 1.0 / 60.0 - """The physics simulation time-step (in seconds). Default is 0.0167 seconds.""" - render_interval: int = 1 """The number of physics simulation steps per rendering step. Default is 1.""" - gravity: tuple[float, float, float] = (0.0, 0.0, -9.81) - """The gravity vector (in m/s^2). Default is (0.0, 0.0, -9.81). - - If set to (0.0, 0.0, 0.0), gravity is disabled. - """ - enable_scene_query_support: bool = False """Enable/disable scene query support for collision shapes. Default is False. @@ -471,36 +195,11 @@ class SimulationCfg: with the GUI enabled. This is to allow certain GUI features to work properly. """ - use_fabric: bool = True - """Enable/disable reading of physics buffers directly. Default is True. - - When running the simulation, updates in the states in the scene is normally synchronized with USD. - This leads to an overhead in reading the data and does not scale well with massive parallelization. - This flag allows disabling the synchronization and reading the data directly from the physics buffers. - - It is recommended to set this flag to :obj:`True` when running the simulation with a large number - of primitives in the scene. - - Note: - When enabled, the GUI will not update the physics parameters in real-time. To enable real-time - updates, please set this flag to :obj:`False`. - - When using GPU simulation, it is required to enable Fabric to visualize updates in the renderer. - Transform updates are propagated to the renderer through Fabric. If Fabric is disabled with GPU simulation, - the renderer will not be able to render any updates in the simulation, although simulation will still be - running under the hood. - """ - - physx: PhysxCfg = PhysxCfg() - """PhysX solver settings. Default is PhysxCfg().""" - - physics_material: RigidBodyMaterialCfg = RigidBodyMaterialCfg() - """Default physics material settings for rigid bodies. Default is RigidBodyMaterialCfg(). + physics_manager_cfg: PhysicsManagerCfg = PhysxManagerCfg() + """Physics manager configuration. Default is PhysxManagerCfg(). - The physics engine defaults to this physics material for all the rigid body prims that do not have any - physics material specified on them. - - The material is created at the path: ``{physics_prim_path}/defaultMaterial``. + This configuration determines which physics manager to use. Override with + a different config (e.g., NewtonManagerCfg) to use a different physics backend. """ render: RenderCfg = RenderCfg() @@ -524,3 +223,6 @@ class SimulationCfg: If :attr:`save_logs_to_file` is True, the logs will be saved to the directory specified by :attr:`log_dir`. If None, the logs will be saved to the temp directory. """ + + visualizer_cfgs: list[VisualizerCfg] | VisualizerCfg | None = None + """The list of visualizer configurations. Default is None.""" diff --git a/source/isaaclab/isaaclab/sim/simulation_context.py b/source/isaaclab/isaaclab/sim/simulation_context.py index 5354c8b381d..f2aca3fcc7c 100644 --- a/source/isaaclab/isaaclab/sim/simulation_context.py +++ b/source/isaaclab/isaaclab/sim/simulation_context.py @@ -3,1042 +3,334 @@ # # SPDX-License-Identifier: BSD-3-Clause -import builtins -import enum -import glob +import gc import logging -import os -import re -import time import traceback -import weakref from collections.abc import Iterator from contextlib import contextmanager -from datetime import datetime from typing import Any -import flatdict -import numpy as np -import toml +import carb import torch +from pxr import Gf, Usd, UsdGeom, UsdPhysics, UsdUtils -import carb -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 pxr import Gf, PhysxSchema, Sdf, Usd, UsdPhysics, UsdUtils +import isaaclab.sim.utils.stage as stage_utils import isaaclab.sim as sim_utils -from isaaclab.utils.logger import configure_logging -from isaaclab.utils.version import get_isaac_sim_version - +from isaaclab.physics import PhysicsManager +from isaaclab.sim.utils import create_new_stage_in_memory +from isaaclab.visualizers import Visualizer from .simulation_cfg import SimulationCfg from .spawners import DomeLightCfg, GroundPlaneCfg -from .utils import bind_physics_material -# import logger logger = logging.getLogger(__name__) -class SimulationContext(_SimulationContext): - """A class to control simulation-related events such as physics stepping and rendering. +class SettingsHelper: + """Helper for typed Carbonite settings access.""" - The simulation context helps control various simulation aspects. This includes: + def __init__(self, settings: "carb.settings.ISettings"): + self._settings = settings - * configure the simulator with different settings such as the physics time-step, the number of physics substeps, - and the physics solver parameters (for more information, see :class:`isaaclab.sim.SimulationCfg`) - * playing, pausing, stepping and stopping the simulation - * adding and removing callbacks to different simulation events such as physics stepping, rendering, etc. + def set(self, name: str, value: Any) -> None: + """Set a Carbonite setting with automatic type routing.""" + if isinstance(value, bool): + self._settings.set_bool(name, value) + elif isinstance(value, int): + self._settings.set_int(name, value) + elif isinstance(value, float): + self._settings.set_float(name, value) + elif isinstance(value, str): + self._settings.set_string(name, value) + elif isinstance(value, (list, tuple)): + self._settings.set(name, value) + else: + raise ValueError(f"Unsupported value type for setting '{name}': {type(value)}") - This class inherits from the :class:`isaacsim.core.api.simulation_context.SimulationContext` class and - adds additional functionalities such as setting up the simulation context with a configuration object, - exposing other commonly used simulator-related functions, and performing version checks of Isaac Sim - to ensure compatibility between releases. + def get(self, name: str) -> Any: + """Get a Carbonite setting value.""" + return self._settings.get(name) - The simulation context is a singleton object. This means that there can only be one instance - of the simulation context at any given time. This is enforced by the parent class. Therefore, it is - not possible to create multiple instances of the simulation context. Instead, the simulation context - can be accessed using the ``instance()`` method. - .. attention:: - Since we only support the `PyTorch `_ backend for simulation, the - simulation context is configured to use the ``torch`` backend by default. This means that - all the data structures used in the simulation are ``torch.Tensor`` objects. +class SimulationContext: + """Controls simulation lifecycle including physics stepping and rendering. - The simulation context can be used in two different modes of operations: + This singleton class manages: - 1. **Standalone python script**: In this mode, the user has full control over the simulation and - can trigger stepping events synchronously (i.e. as a blocking call). In this case the user - has to manually call :meth:`step` step the physics simulation and :meth:`render` to - render the scene. - 2. **Omniverse extension**: In this mode, the user has limited control over the simulation stepping - and all the simulation events are triggered asynchronously (i.e. as a non-blocking call). In this - case, the user can only trigger the simulation to start, pause, and stop. The simulation takes - care of stepping the physics simulation and rendering the scene. + * Physics configuration (time-step, solver parameters via :class:`isaaclab.sim.SimulationCfg`) + * Simulation state (play, pause, step, stop) + * Rendering and visualization - Based on above, for most functions in this class there is an equivalent function that is suffixed - with ``_async``. The ``_async`` functions are used in the Omniverse extension mode and - the non-``_async`` functions are used in the standalone python script mode. + The singleton instance can be accessed using the ``instance()`` class method. """ - class RenderMode(enum.IntEnum): - """Different rendering modes for the simulation. - - Render modes correspond to how the viewport and other UI elements (such as listeners to keyboard or mouse - events) are updated. There are three main components that can be updated when the simulation is rendered: - - 1. **UI elements and other extensions**: These are UI elements (such as buttons, sliders, etc.) and other - extensions that are running in the background that need to be updated when the simulation is running. - 2. **Cameras**: These are typically based on Hydra textures and are used to render the scene from different - viewpoints. They can be attached to a viewport or be used independently to render the scene. - 3. **Viewports**: These are windows where you can see the rendered scene. - - Updating each of the above components has a different overhead. For example, updating the viewports is - computationally expensive compared to updating the UI elements. Therefore, it is useful to be able to - control what is updated when the simulation is rendered. This is where the render mode comes in. There are - four different render modes: + # SINGLETON PATTERN - * :attr:`NO_GUI_OR_RENDERING`: The simulation is running without a GUI and off-screen rendering flag - is disabled, so none of the above are updated. - * :attr:`NO_RENDERING`: No rendering, where only 1 is updated at a lower rate. - * :attr:`PARTIAL_RENDERING`: Partial rendering, where only 1 and 2 are updated. - * :attr:`FULL_RENDERING`: Full rendering, where everything (1, 2, 3) is updated. + _instance: "SimulationContext | None" = None - .. _Viewports: https://docs.omniverse.nvidia.com/extensions/latest/ext_viewport.html - """ + def __new__(cls, cfg: SimulationCfg | None = None): + """Enforce singleton pattern.""" + if cls._instance is not None: + return cls._instance + return super().__new__(cls) - NO_GUI_OR_RENDERING = -1 - """The simulation is running without a GUI and off-screen rendering is disabled.""" - NO_RENDERING = 0 - """No rendering, where only other UI elements are updated at a lower rate.""" - PARTIAL_RENDERING = 1 - """Partial rendering, where the simulation cameras and UI elements are updated.""" - FULL_RENDERING = 2 - """Full rendering, where all the simulation viewports, cameras and UI elements are updated.""" + @classmethod + def instance(cls) -> "SimulationContext | None": + """Get the singleton instance, or None if not created.""" + return cls._instance def __init__(self, cfg: SimulationCfg | None = None): - """Creates a simulation context to control the simulator. + """Initialize the simulation context. Args: - cfg: The configuration of the simulation. Defaults to None, - in which case the default configuration is used. + cfg: Simulation configuration. Defaults to None (uses default config). """ - # store input - if cfg is None: - cfg = SimulationCfg() - # check that the config is valid - cfg.validate() - self.cfg = cfg - # check that simulation is running - if sim_utils.get_current_stage() is None: - raise RuntimeError("The stage has not been created. Did you run the simulator?") - - # setup logger - self.logger = configure_logging( - logging_level=self.cfg.logging_level, - save_logs_to_file=self.cfg.save_logs_to_file, - log_dir=self.cfg.log_dir, - ) - - # create stage in memory if requested - if self.cfg.create_stage_in_memory: - self._initial_stage = sim_utils.create_new_stage_in_memory() - else: - self._initial_stage = omni.usd.get_context().get_stage() - # cache stage if it is not already cached - stage_cache = UsdUtils.StageCache.Get() - stage_id = stage_cache.GetId(self._initial_stage).ToLongInt() - if stage_id < 0: - stage_cache.Insert(self._initial_stage) - - # acquire settings interface - self.carb_settings = carb.settings.get_settings() - - # apply carb physics settings - self._apply_physics_settings() - - # note: we read this once since it is not expected to change during runtime - # read flag for whether a local GUI is enabled - self._local_gui = self.carb_settings.get("/app/window/enabled") - # read flag for whether livestreaming GUI is enabled - self._livestream_gui = self.carb_settings.get("/app/livestream/enabled") - # read flag for whether XR GUI is enabled - self._xr_gui = self.carb_settings.get("/app/xr/enabled") - - # read flags anim recording config and init timestamps - self._setup_anim_recording() - - # read flag for whether the Isaac Lab viewport capture pipeline will be used, - # casting None to False if the flag doesn't exist - # this flag is set from the AppLauncher class - self._offscreen_render = bool(self.carb_settings.get("/isaaclab/render/offscreen")) - # read flag for whether the default viewport should be enabled - self._render_viewport = bool(self.carb_settings.get("/isaaclab/render/active_viewport")) - # flag for whether any GUI will be rendered (local, livestreamed or viewport) - self._has_gui = self._local_gui or self._livestream_gui or self._xr_gui - - # apply render settings from render config - self._apply_render_settings_from_cfg() - - # store the default render mode - if not self._has_gui and not self._offscreen_render: - # set default render mode - # note: this is the terminal state: cannot exit from this render mode - self.render_mode = self.RenderMode.NO_GUI_OR_RENDERING - # set viewport context to None - self._viewport_context = None - self._viewport_window = None - elif not self._has_gui and self._offscreen_render: - # set default render mode - # note: this is the terminal state: cannot exit from this render mode - self.render_mode = self.RenderMode.PARTIAL_RENDERING - # set viewport context to None - self._viewport_context = None - self._viewport_window = 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.updates_enabled = True # pyright: ignore [reportOptionalMemberAccess] - # acquire viewport window - # TODO @mayank: Why not just use get_active_viewport_and_window() directly? - self._viewport_window = ui.Workspace.get_window("Viewport") - # counter for periodic rendering - self._render_throttle_counter = 0 - # rendering frequency in terms of number of render calls - self._render_throttle_period = 5 - - # 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 - - # override enable scene querying if rendering is enabled - # this is needed for some GUI features - if self._has_gui: - self.cfg.enable_scene_query_support = True - # set up flatcache/fabric interface (default is None) - # this is needed to flush the flatcache data into Hydra manually when calling `render()` - # ref: https://docs.omniverse.nvidia.com/prod_extensions/prod_extensions/ext_physics.html - # note: need to do this here because super().__init__ calls render and this variable is needed - self._fabric_iface = None - - # create a tensor for gravity - # note: this line is needed to create a "tensor" in the device to avoid issues with torch 2.1 onwards. - # the issue is with some heap memory corruption when torch tensor is created inside the asset class. - # you can reproduce the issue by commenting out this line and running the test `test_articulation.py`. - self._gravity_tensor = torch.tensor(self.cfg.gravity, dtype=torch.float32, device=self.cfg.device) - - # define a global variable to store the exceptions raised in the callback stack - builtins.ISAACLAB_CALLBACK_EXCEPTION = None - - # add callback to deal the simulation app when simulation is stopped. - # this is needed because physics views go invalid once we stop the simulation - if not builtins.ISAAC_LAUNCHED_FROM_TERMINAL: - timeline_event_stream = omni.timeline.get_timeline_interface().get_timeline_event_stream() - self._app_control_on_stop_handle = timeline_event_stream.create_subscription_to_pop_by_type( - int(omni.timeline.TimelineEventType.STOP), - lambda *args, obj=weakref.proxy(self): obj._app_control_on_stop_handle_fn(*args), - order=15, - ) - else: - self._app_control_on_stop_handle = None - self._disable_app_control_on_stop_handle = False - - # flatten out the simulation dictionary - sim_params = self.cfg.to_dict() - if sim_params is not None: - if "physx" in sim_params: - physx_params = sim_params.pop("physx") - sim_params.update(physx_params) - - # add warning about enabling stabilization for large step sizes - if not self.cfg.physx.enable_stabilization and (self.cfg.dt > 0.0333): - self.logger.warning( - "Large simulation step size (> 0.0333 seconds) is not recommended without enabling stabilization." - " Consider setting the `enable_stabilization` flag to True in the PhysxCfg, or reducing the" - " simulation step size if you run into physics issues." - ) + if type(self)._instance is not None: + return # Already initialized - # 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) - - # obtain the parsed device - # This device should be the same as "self.cfg.device". However, for cases, where users specify the device - # as "cuda" and not "cuda:X", then it fetches the current device from SimulationManager. - # 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() - - # create a simulation context to control the simulator - if get_isaac_sim_version().major < 5: - # stage arg is not supported before isaac sim 5.0 - super().__init__( - stage_units_in_meters=1.0, - physics_dt=self.cfg.dt, - rendering_dt=self.cfg.dt * self.cfg.render_interval, - backend="torch", - sim_params=sim_params, - physics_prim_path=self.cfg.physics_prim_path, - device=self.cfg.device, - ) - else: - super().__init__( - stage_units_in_meters=1.0, - physics_dt=self.cfg.dt, - rendering_dt=self.cfg.dt * self.cfg.render_interval, - backend="torch", - sim_params=sim_params, - physics_prim_path=self.cfg.physics_prim_path, - device=self.cfg.device, - stage=self._initial_stage, - ) - - """ - Properties - Override. - """ - - @property - def device(self) -> str: - """Device used by the simulation. + # Store config + self.cfg = SimulationCfg() if cfg is None else cfg + self.device = self.cfg.device - Note: - In Omniverse, it is possible to configure multiple GPUs for rendering, while physics engine - operates on a single GPU. This function returns the device that is used for physics simulation. - """ - return self._physics_device - - """ - Operations - New. - """ - - def has_gui(self) -> bool: - """Returns whether the simulation has a GUI enabled. - - True if the simulation has a GUI enabled either locally or live-streamed. - """ - return self._has_gui + # Get existing stage or create new one in memory + stage_cache = UsdUtils.StageCache.Get() + all_stages = stage_cache.GetAllStages() if stage_cache.Size() > 0 else [] # type: ignore[union-attr] + self.stage = all_stages[0] if all_stages else create_new_stage_in_memory() - def has_rtx_sensors(self) -> bool: - """Returns whether the simulation has any RTX-rendering related sensors. + # Cache stage in USD cache + stage_id = stage_cache.GetId(self.stage).ToLongInt() # type: ignore[union-attr] + if stage_id < 0: + stage_cache.Insert(self.stage) # type: ignore[union-attr] - This function returns the value of the simulation parameter ``"/isaaclab/render/rtx_sensors"``. - The parameter is set to True when instances of RTX-related sensors (cameras or LiDARs) are - created using Isaac Lab's sensor classes. + # Set as current stage in thread-local context for get_current_stage() + stage_utils._context.stage = self.stage - True if the simulation has RTX sensors (such as USD Cameras or LiDARs). + # Acquire settings interface and create helper + self.carb_settings = carb.settings.get_settings() + self._settings_helper = SettingsHelper(self.carb_settings) + + # Initialize USD physics scene and physics manager + self._init_usd_physics_scene() + self._physics_manager_cfg = self.cfg.physics_manager_cfg + self.physics_manager: type[PhysicsManager] = self._physics_manager_cfg.class_type + self.physics_manager.initialize(self) + + # Initialize visualizers + self._init_visualizers() + + # Simulation state + self._is_playing = False + self._is_stopped = True + type(self)._instance = self # Mark as valid singleton only after successful init + + def _init_usd_physics_scene(self) -> None: + """Create and configure the USD physics scene.""" + cfg = self.cfg.physics_manager_cfg + with sim_utils.use_stage(self.stage): + # Set stage conventions for metric units + UsdGeom.SetStageUpAxis(self.stage, "Z") + UsdGeom.SetStageMetersPerUnit(self.stage, 1.0) + UsdPhysics.SetStageKilogramsPerUnit(self.stage, 1.0) + + # Find and delete any existing physics scene + for prim in self.stage.Traverse(): + if prim.GetTypeName() == "PhysicsScene": + sim_utils.delete_prim(prim.GetPath().pathString, stage=self.stage) + + # Create a new physics scene + if self.stage.GetPrimAtPath(cfg.physics_prim_path).IsValid(): + raise RuntimeError(f"A prim already exists at path '{cfg.physics_prim_path}'.") + + physics_scene = UsdPhysics.Scene.Define(self.stage, cfg.physics_prim_path) + + # Pre-create gravity tensor to avoid torch heap corruption issues (torch 2.1+) + gravity = torch.tensor(cfg.gravity, dtype=torch.float32, device=cfg.device) + gravity_magnitude = torch.norm(gravity).item() + + if gravity_magnitude == 0.0: + gravity_direction = [0.0, 0.0, -1.0] + else: + gravity_direction = (gravity / gravity_magnitude).tolist() - For more information, please check `NVIDIA RTX documentation`_. + physics_scene.CreateGravityDirectionAttr(Gf.Vec3f(*gravity_direction)) + physics_scene.CreateGravityMagnitudeAttr(gravity_magnitude) - .. _NVIDIA RTX documentation: https://developer.nvidia.com/rendering-technologies - """ - return self._settings.get_as_bool("/isaaclab/render/rtx_sensors") + @property + def physics_sim_view(self): + """Returns the physics simulation view.""" + return self.physics_manager.get_physics_sim_view() def is_fabric_enabled(self) -> bool: - """Returns whether the fabric interface is enabled. - - When fabric interface is enabled, USD read/write operations are disabled. Instead all applications - read and write the simulation state directly from the fabric interface. This reduces a lot of overhead - that occurs during USD read/write operations. - - For more information, please check `Fabric documentation`_. - - .. _Fabric documentation: https://docs.omniverse.nvidia.com/kit/docs/usdrt/latest/docs/usd_fabric_usdrt.html - """ - return self._fabric_iface is not None - - def get_version(self) -> tuple[int, int, int]: - """Returns the version of the simulator. - - The returned tuple contains the following information: - - * Major version: This is the year of the release (e.g. 2022). - * Minor version: This is the half-year of the release (e.g. 1 or 2). - * Patch version: This is the patch number of the release (e.g. 0). - - .. attention:: - This function is deprecated and will be removed in the future. - We recommend using :func:`isaaclab.utils.version.get_isaac_sim_version` - instead of this function. - - Returns: - A tuple containing the major, minor, and patch versions. - - Example: - >>> sim = SimulationContext() - >>> sim.get_version() - (2022, 1, 0) - """ - return get_isaac_sim_version().major, get_isaac_sim_version().minor, get_isaac_sim_version().micro - - """ - Operations - New utilities. - """ - - def set_camera_view( - self, - eye: tuple[float, float, float], - target: tuple[float, float, float], - camera_prim_path: str = "/OmniverseKit_Persp", - ): - """Set the location and target of the viewport camera in the stage. - - Note: - This is a wrapper around the :math:`isaacsim.core.utils.viewports.set_camera_view` function. - It is provided here for convenience to reduce the amount of imports needed. - - Args: - eye: The location of the camera eye. - target: The location of the camera target. - camera_prim_path: The path to the camera primitive in the stage. Defaults to - "/OmniverseKit_Persp". - """ - # 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) - - def set_render_mode(self, mode: RenderMode): - """Change the current render mode of the simulation. - - Please see :class:`RenderMode` for more information on the different render modes. - - .. note:: - When no GUI is available (locally or livestreamed), we do not need to choose whether the viewport - needs to render or not (since there is no GUI). Thus, in this case, calling the function will not - change the render mode. - - Args: - mode (RenderMode): The rendering mode. If different than SimulationContext's rendering mode, - SimulationContext's mode is changed to the new mode. - - Raises: - ValueError: If the input mode is not supported. - """ - # check if mode change is possible -- not possible when no GUI is available - if not self._has_gui: - self.logger.warning( - f"Cannot change render mode when GUI is disabled. Using the default render mode: {self.render_mode}." - ) - return - # check if there is a mode change - # note: this is mostly needed for GUI when we want to switch between full rendering and no rendering. - if mode != self.render_mode: - if mode == self.RenderMode.FULL_RENDERING: - # display the viewport and enable updates - self._viewport_context.updates_enabled = True # pyright: ignore [reportOptionalMemberAccess] - self._viewport_window.visible = True # pyright: ignore [reportOptionalMemberAccess] - elif mode == self.RenderMode.PARTIAL_RENDERING: - # hide the viewport and disable updates - self._viewport_context.updates_enabled = False # pyright: ignore [reportOptionalMemberAccess] - self._viewport_window.visible = False # pyright: ignore [reportOptionalMemberAccess] - elif mode == self.RenderMode.NO_RENDERING: - # hide the viewport and disable updates - if self._viewport_context is not None: - self._viewport_context.updates_enabled = False # pyright: ignore [reportOptionalMemberAccess] - self._viewport_window.visible = False # pyright: ignore [reportOptionalMemberAccess] - # reset the throttle counter - self._render_throttle_counter = 0 + """Returns whether the fabric interface is enabled.""" + return self.carb_settings.get_as_bool("/isaaclab/fabric_enabled") + + def get_physics_dt(self) -> float: + """Returns the physics time step.""" + return self.physics_manager.get_physics_dt() + + # VISUALIZER MANAGEMENT + def _init_visualizers(self) -> None: + """Initialize visualizers based on config and settings.""" + self._visualizers: list[Visualizer] = [] + self._viz_dt = self.cfg.physics_manager_cfg.dt * self.cfg.render_interval + + # Determine which visualizers to create + viz_str = "omniverse" # Default + requested = [v.strip() for v in viz_str.split(",") if v.strip()] + + if len(requested) > 0: + # Get or create visualizer configs + cfg_list = self.cfg.visualizer_cfgs + from isaaclab_physx.visualizers import PhysxOVVisualizerCfg + type_map = {"omniverse": PhysxOVVisualizerCfg} + viz_cfgs = [] + if cfg_list is None: + for viz_type in requested: + viz_cfgs.append(type_map[viz_type]()) else: - raise ValueError(f"Unsupported render mode: {mode}! Please check `RenderMode` for details.") - # update render mode - self.render_mode = mode - - def set_setting(self, name: str, value: Any): - """Set simulation settings using the Carbonite SDK. + viz_cfgs = cfg_list if isinstance(cfg_list, list) else [cfg_list] + + # Create and initialize each visualizer + for cfg in viz_cfgs: + self._visualizers.append(cfg.create_visualizer()) + # build scene data for visualizer initialization + if cfg.visualizer_type in ("newton", "rerun"): + scene_data = {"scene_data_provider": None} + elif cfg.visualizer_type == "omniverse": + scene_data = {"usd_stage": self.stage, "simulation_context": self} + else: + scene_data = {} + self._visualizers[-1].initialize(scene_data) + logger.info(f"Initialized visualizer: {type(self._visualizers[-1]).__name__}") - .. note:: - If the input setting name does not exist, it will be created. If it does exist, the value will be - overwritten. Please make sure to use the correct setting name. - - To understand the settings interface, please refer to the - `Carbonite SDK `_ - documentation. - - Args: - name: The name of the setting. - value: The value of the setting. - """ - # Route through typed setters for correctness and consistency for common scalar types. - if isinstance(value, bool): - self.carb_settings.set_bool(name, value) - elif isinstance(value, int): - self.carb_settings.set_int(name, value) - elif isinstance(value, float): - self.carb_settings.set_float(name, value) - elif isinstance(value, str): - self.carb_settings.set_string(name, value) - elif isinstance(value, (list, tuple)): - self.carb_settings.set(name, value) - else: - raise ValueError(f"Unsupported value type for setting '{name}': {type(value)}") - - def get_setting(self, name: str) -> Any: - """Read the simulation setting using the Carbonite SDK. - - Args: - name: The name of the setting. - - Returns: - The value of the setting. - """ - return self.carb_settings.get(name) - - def get_initial_stage(self) -> Usd.Stage: - """Returns stage handle used during scene creation. - - Returns: - The stage used during scene creation. - """ - return self._initial_stage + @property + def visualizers(self) -> list[Visualizer]: + """Returns the list of active visualizers.""" + return self._visualizers - """ - Operations - Override (standalone) - """ + def get_rendering_dt(self) -> float: + """Returns the rendering time step.""" + return self._viz_dt - def reset(self, soft: bool = False): - self._disable_app_control_on_stop_handle = True - # check if we need to raise an exception that was raised in a callback - if builtins.ISAACLAB_CALLBACK_EXCEPTION is not None: - exception_to_raise = builtins.ISAACLAB_CALLBACK_EXCEPTION - builtins.ISAACLAB_CALLBACK_EXCEPTION = None - raise exception_to_raise - super().reset(soft=soft) - # app.update() may be changing the cuda device in reset, so we force it back to our desired device here - if "cuda" in self.device: - torch.cuda.set_device(self.device) - # enable kinematic rendering with fabric - if self.physics_sim_view: - self.physics_sim_view._backend.initialize_kinematic_bodies() - # perform additional rendering steps to warm up replicator buffers - # this is only needed for the first time we set the simulation - if not soft: - for _ in range(2): - self.render() - self._disable_app_control_on_stop_handle = False + def set_camera_view(self, eye: tuple, target: tuple) -> None: + """Set camera view on all visualizers that support it.""" + for viz in self._visualizers: + viz.set_camera_view(eye, target) def forward(self) -> None: - """Updates articulation kinematics and fabric for rendering.""" - if self._fabric_iface is not None: - if self.physics_sim_view is not None and self.is_playing(): - # Update the articulations' link's poses before rendering - self.physics_sim_view.update_articulations_kinematic() - self._update_fabric(0.0, 0.0) - - def step(self, render: bool = True): - """Steps the simulation. + """Update kinematics without stepping physics.""" + self.physics_manager.forward() - .. note:: - This function blocks if the timeline is paused. It only returns when the timeline is playing. + def reset(self, soft: bool = False) -> None: + """Reset the simulation. Args: - render: Whether to render the scene after stepping the physics simulation. - If set to False, the scene is not rendered and only the physics simulation is stepped. + soft: If True, skip full reinitialization. """ - # check if we need to raise an exception that was raised in a callback - if builtins.ISAACLAB_CALLBACK_EXCEPTION is not None: - exception_to_raise = builtins.ISAACLAB_CALLBACK_EXCEPTION - builtins.ISAACLAB_CALLBACK_EXCEPTION = None - raise exception_to_raise - - # update anim recording if needed - if self._anim_recording_enabled: - is_anim_recording_finished = self._update_anim_recording() - if is_anim_recording_finished: - logger.warning("[INFO][SimulationContext]: Animation recording finished. Closing app.") - self._app.shutdown() - - # check if the simulation timeline is paused. in that case keep stepping until it is playing - if not self.is_playing(): - # step the simulator (but not the physics) to have UI still active - while not self.is_playing(): - self.render() - # meantime if someone stops, break out of the loop - if self.is_stopped(): - break - # need to do one step to refresh the app - # reason: physics has to parse the scene again and inform other extensions like hydra-delegate. - # without this the app becomes unresponsive. - # FIXME: This steps physics as well, which we is not good in general. - self.app.update() - - # step the simulation - super().step(render=render) - - # app.update() may be changing the cuda device in step, so we force it back to our desired device here - if "cuda" in self.device: - torch.cuda.set_device(self.device) - - def render(self, mode: RenderMode | None = None): - """Refreshes the rendering components including UI elements and view-ports depending on the render mode. - - This function is used to refresh the rendering components of the simulation. This includes updating the - view-ports, UI elements, and other extensions (besides physics simulation) that are running in the - background. The rendering components are refreshed based on the render mode. - - Please see :class:`RenderMode` for more information on the different render modes. + self.physics_manager.reset(soft) + for viz in self._visualizers: + viz.reset(soft) + self._is_playing = True + self._is_stopped = False + + def step(self, render: bool = True) -> None: + """Step physics, update visualizers, and optionally render. Args: - mode: The rendering mode. Defaults to None, in which case the current rendering mode is used. + render: Whether to render the scene after stepping. Defaults to True. """ - # check if we need to raise an exception that was raised in a callback - if builtins.ISAACLAB_CALLBACK_EXCEPTION is not None: - exception_to_raise = builtins.ISAACLAB_CALLBACK_EXCEPTION - builtins.ISAACLAB_CALLBACK_EXCEPTION = None - raise exception_to_raise - # check if we need to change the render mode - if mode is not None: - self.set_render_mode(mode) - # render based on the render mode - if self.render_mode == self.RenderMode.NO_GUI_OR_RENDERING: - # we never want to render anything here (this is for complete headless mode) - pass - elif self.render_mode == self.RenderMode.NO_RENDERING: - # throttle the rendering frequency to keep the UI responsive - self._render_throttle_counter += 1 - if self._render_throttle_counter % self._render_throttle_period == 0: - self._render_throttle_counter = 0 - # here we don't render viewport so don't need to flush fabric data - # note: we don't call super().render() anymore because they do flush the fabric data - self.set_setting("/app/player/playSimulations", False) - self._app.update() - self.set_setting("/app/player/playSimulations", True) - else: - # manually flush the fabric data to update Hydra textures - self.forward() - # render the simulation - # note: we don't call super().render() anymore because they do above operation inside - # and we don't want to do it twice. We may remove it once we drop support for Isaac Sim 2022.2. - self.set_setting("/app/player/playSimulations", False) - self._app.update() - self.set_setting("/app/player/playSimulations", True) - - # app.update() may be changing the cuda device, so we force it back to our desired device here - if "cuda" in self.device: - torch.cuda.set_device(self.device) - - """ - Operations - Override (extension) - """ - - async def reset_async(self, soft: bool = False): - # need to load all "physics" information from the USD file - if not soft: - omni.physx.acquire_physx_interface().force_load_physics_from_usd() - # play the simulation - await super().reset_async(soft=soft) - - """ - Initialization/Destruction - Override. - """ + self.physics_manager.step() + if render: + self.render() + + def render(self, mode: int | None = None) -> None: + """Render the scene via all active visualizers.""" + self.physics_manager.forward() + for viz in self._visualizers: + if not viz.is_rendering_paused() and viz.is_running(): + viz.step(self.get_rendering_dt(), state=None) + + def play(self) -> None: + """Start or resume the simulation.""" + self.physics_manager.play() + for viz in self._visualizers: + viz.play() + self._is_playing = True + self._is_stopped = False + + def pause(self) -> None: + """Pause the simulation (can be resumed with play).""" + self.physics_manager.pause() + for viz in self._visualizers: + viz.pause() + self._is_playing = False + + def stop(self) -> None: + """Stop the simulation completely.""" + self.physics_manager.stop() + for viz in self._visualizers: + viz.stop() + self._is_playing = False + self._is_stopped = True + + def is_playing(self) -> bool: + """Returns True if simulation is playing (not paused or stopped).""" + return self._is_playing + + def is_stopped(self) -> bool: + """Returns True if simulation is stopped (not just paused).""" + return self._is_stopped + + def set_setting(self, name: str, value: Any) -> None: + """Set a Carbonite setting value.""" + self._settings_helper.set(name, value) - def _init_stage(self, *args, **kwargs) -> Usd.Stage: - _ = super()._init_stage(*args, **kwargs) - with sim_utils.use_stage(self.get_initial_stage()): - # a stage update here is needed for the case when physics_dt != rendering_dt, otherwise the app crashes - # when in headless mode - self.set_setting("/app/player/playSimulations", False) - self._app.update() - self.set_setting("/app/player/playSimulations", True) - # set additional physx parameters and bind material - self._set_additional_physx_params() - # load flatcache/fabric interface - self._load_fabric_interface() - # return the stage - return self.stage - - async def _initialize_stage_async(self, *args, **kwargs) -> Usd.Stage: - await super()._initialize_stage_async(*args, **kwargs) - # set additional physx parameters and bind material - self._set_additional_physx_params() - # load flatcache/fabric interface - self._load_fabric_interface() - # return the stage - return self.stage + def get_setting(self, name: str) -> Any: + """Get a Carbonite setting value.""" + return self._settings_helper.get(name) @classmethod - def clear_instance(cls): - # clear the callback + def clear_instance(cls) -> None: + """Clean up resources and clear the singleton instance.""" if cls._instance is not None: - if cls._instance._app_control_on_stop_handle is not None: - cls._instance._app_control_on_stop_handle.unsubscribe() - cls._instance._app_control_on_stop_handle = None - # call parent to clear the instance - super().clear_instance() + # Clear stage contents first + cls.clear_stage() - """ - Helper Functions - """ + # Close physics manager + cls._instance.physics_manager.close() - def _apply_physics_settings(self): - """Sets various carb physics settings.""" - # enable hydra scene-graph instancing - # note: this allows rendering of instanceable assets on the GUI - self.carb_settings.set_bool("/persistent/omnihydra/useSceneGraphInstancing", True) - # change dispatcher to use the default dispatcher in PhysX SDK instead of carb tasking - # note: dispatcher handles how threads are launched for multi-threaded physics - self.carb_settings.set_bool("/physics/physxDispatcher", True) - # disable contact processing in omni.physx - # note: we disable it by default to avoid the overhead of contact processing when it isn't needed. - # The physics flag gets enabled when a contact sensor is created. - if hasattr(self.cfg, "disable_contact_processing"): - self.logger.warning( - "The `disable_contact_processing` attribute is deprecated and always set to True" - " to avoid unnecessary overhead. Contact processing is automatically enabled when" - " a contact sensor is created, so manual configuration is no longer required." - ) - # FIXME: From investigation, it seems this flag only affects CPU physics. For GPU physics, contacts - # are always processed. The issue is reported to the PhysX team by @mmittal. - self.carb_settings.set_bool("/physics/disableContactProcessing", True) - # disable custom geometry for cylinder and cone collision shapes to allow contact reporting for them - # reason: cylinders and cones aren't natively supported by PhysX so we need to use custom geometry flags - # reference: https://nvidia-omniverse.github.io/PhysX/physx/5.4.1/docs/Geometry.html?highlight=capsule#geometry - self.carb_settings.set_bool("/physics/collisionConeCustomGeometry", False) - self.carb_settings.set_bool("/physics/collisionCylinderCustomGeometry", False) - # hide the Simulation Settings window - self.carb_settings.set_bool("/physics/autoPopupSimulationOutputWindow", False) - self.carb_settings.set_bool("/physics/visualizationSimulationOutput", False) - # set fabric enabled flag - self.carb_settings.set_bool("/physics/fabricEnabled", self.cfg.use_fabric) - - def _apply_render_settings_from_cfg(self): # noqa: C901 - """Sets rtx settings specified in the RenderCfg.""" - - # define mapping of user-friendly RenderCfg names to native carb names - rendering_setting_name_mapping = { - "enable_translucency": "/rtx/translucency/enabled", - "enable_reflections": "/rtx/reflections/enabled", - "enable_global_illumination": "/rtx/indirectDiffuse/enabled", - "enable_dlssg": "/rtx-transient/dlssg/enabled", - "enable_dl_denoiser": "/rtx-transient/dldenoiser/enabled", - "dlss_mode": "/rtx/post/dlss/execMode", - "enable_direct_lighting": "/rtx/directLighting/enabled", - "samples_per_pixel": "/rtx/directLighting/sampledLighting/samplesPerPixel", - "enable_shadows": "/rtx/shadows/enabled", - "enable_ambient_occlusion": "/rtx/ambientOcclusion/enabled", - "dome_light_upper_lower_strategy": "/rtx/domeLight/upperLowerStrategy", - "ambient_light_intensity": "/rtx/sceneDb/ambientLightIntensity", - "ambient_occlusion_denoiser_mode": "/rtx/ambientOcclusion/denoiserMode", - "subpixel_mode": "/rtx/raytracing/subpixel/mode", - "enable_cached_raytracing": "/rtx/raytracing/cached/enabled", - "max_samples_per_launch": "/rtx/pathtracing/maxSamplesPerLaunch", - "view_tile_limit": "/rtx/viewTile/limit", - # RT2 settings - "max_bounces": "/rtx/rtpt/maxBounces", - "split_glass": "/rtx/rtpt/splitGlass", - "split_clearcoat": "/rtx/rtpt/splitClearcoat", - "split_rough_reflection": "/rtx/rtpt/splitRoughReflection", - } - - not_carb_settings = ["rendering_mode", "carb_settings", "antialiasing_mode"] - - # grab the rendering mode using the following priority: - # 1. command line argument --rendering_mode, if provided - # 2. rendering_mode from Render Config, if set - # 3. lastly, default to "balanced" mode, if neither is specified - rendering_mode = self.carb_settings.get("/isaaclab/rendering/rendering_mode") - if not rendering_mode: - rendering_mode = self.cfg.render.rendering_mode - if not rendering_mode: - rendering_mode = "balanced" - - # set preset settings (same behavior as the CLI arg --rendering_mode) - if rendering_mode is not None: - # check if preset is supported - supported_rendering_modes = ["performance", "balanced", "quality"] - if rendering_mode not in supported_rendering_modes: - raise ValueError( - f"RenderCfg rendering mode '{rendering_mode}' not in supported modes {supported_rendering_modes}." - ) - - # grab isaac lab apps path - isaaclab_app_exp_path = os.path.join(os.path.dirname(os.path.abspath(__file__)), *[".."] * 4, "apps") - # for Isaac Sim 5.0 compatibility, we use the 5.X rendering mode app files in a different folder - if get_isaac_sim_version().major < 6: - isaaclab_app_exp_path = os.path.join(isaaclab_app_exp_path, "isaacsim_5") - - # grab preset settings - preset_filename = os.path.join(isaaclab_app_exp_path, f"rendering_modes/{rendering_mode}.kit") - with open(preset_filename) as file: - preset_dict = toml.load(file) - preset_dict = dict(flatdict.FlatDict(preset_dict, delimiter=".")) - - # set presets - for key, value in preset_dict.items(): - key = "/" + key.replace(".", "/") # convert to carb setting format - self.set_setting(key, value) - - # set user-friendly named settings - for key, value in vars(self.cfg.render).items(): - if value is None or key in not_carb_settings: - # skip unset settings and non-carb settings - continue - if key not in rendering_setting_name_mapping: - raise ValueError( - f"'{key}' in RenderCfg not found. Note: internal 'rendering_setting_name_mapping' dictionary might" - " need to be updated." - ) - key = rendering_setting_name_mapping[key] - self.set_setting(key, value) - - # set general carb settings - carb_settings = self.cfg.render.carb_settings - if carb_settings is not None: - for key, value in carb_settings.items(): - if "_" in key: - key = "/" + key.replace("_", "/") # convert from python variable style string - elif "." in key: - key = "/" + key.replace(".", "/") # convert from .kit file style string - if self.get_setting(key) is None: - raise ValueError(f"'{key}' in RenderCfg.general_parameters does not map to a carb setting.") - self.set_setting(key, value) - - # set denoiser mode - if self.cfg.render.antialiasing_mode is not None: - try: - import omni.replicator.core as rep - - rep.settings.set_render_rtx_realtime(antialiasing=self.cfg.render.antialiasing_mode) - except Exception: - pass - - # WAR: Ensure /rtx/renderMode RaytracedLighting is correctly cased. - if self.carb_settings.get("/rtx/rendermode").lower() == "raytracedlighting": - self.carb_settings.set_string("/rtx/rendermode", "RaytracedLighting") - - def _set_additional_physx_params(self): - """Sets additional PhysX parameters that are not directly supported by the parent class.""" - # obtain the physics scene api - physics_scene: UsdPhysics.Scene = self._physics_context._physics_scene - physx_scene_api: PhysxSchema.PhysxSceneAPI = self._physics_context._physx_scene_api - # assert that scene api is not None - if physx_scene_api is None: - raise RuntimeError("Physics scene API is None! Please create the scene first.") - # set parameters not directly supported by the constructor - # -- Continuous Collision Detection (CCD) - # ref: https://nvidia-omniverse.github.io/PhysX/physx/5.4.1/docs/AdvancedCollisionDetection.html?highlight=ccd#continuous-collision-detection - self._physics_context.enable_ccd(self.cfg.physx.enable_ccd) - # -- GPU collision stack size - physx_scene_api.CreateGpuCollisionStackSizeAttr(self.cfg.physx.gpu_collision_stack_size) - # -- Improved determinism by PhysX - physx_scene_api.CreateEnableEnhancedDeterminismAttr(self.cfg.physx.enable_enhanced_determinism) - # -- Set solve_articulation_contact_last by add attribute to the PhysxScene prim, and add attribute there. - physx_prim = physx_scene_api.GetPrim() - physx_prim.CreateAttribute("physxScene:solveArticulationContactLast", Sdf.ValueTypeNames.Bool).Set( - self.cfg.physx.solve_articulation_contact_last - ) - # -- Enable external forces every iteration, helps improve the accuracy of velocity updates. - - if self.cfg.physx.solver_type == 1: - if not self.cfg.physx.enable_external_forces_every_iteration: - logger.warning( - "The `enable_external_forces_every_iteration` parameter in the PhysxCfg is set to False. If you are" - " experiencing noisy velocities, consider enabling this flag. You may need to slightly increase the" - " number of velocity iterations (setting it to 1 or 2 rather than 0), together with this flag, to" - " improve the accuracy of velocity updates." - ) - physx_scene_api.CreateEnableExternalForcesEveryIterationAttr( - self.cfg.physx.enable_external_forces_every_iteration - ) + # Close all visualizers + for viz in cls._instance._visualizers: + viz.close() + cls._instance._visualizers.clear() - # -- Gravity - # note: Isaac sim only takes the "up-axis" as the gravity direction. But physics allows any direction so we - # need to convert the gravity vector to a direction and magnitude pair explicitly. - gravity = np.asarray(self.cfg.gravity) - gravity_magnitude = np.linalg.norm(gravity) + # Remove stage from cache + stage_cache = UsdUtils.StageCache.Get() + stage_id = stage_cache.GetId(cls._instance.stage).ToLongInt() # type: ignore[union-attr] + if stage_id > 0: + stage_cache.Erase(cls._instance.stage) # type: ignore[union-attr] - # Avoid division by zero - if gravity_magnitude != 0.0: - gravity_direction = gravity / gravity_magnitude - else: - gravity_direction = gravity - - physics_scene.CreateGravityDirectionAttr(Gf.Vec3f(*gravity_direction)) - physics_scene.CreateGravityMagnitudeAttr(gravity_magnitude) - - # position iteration count - physx_scene_api.CreateMinPositionIterationCountAttr(self.cfg.physx.min_position_iteration_count) - physx_scene_api.CreateMaxPositionIterationCountAttr(self.cfg.physx.max_position_iteration_count) - # velocity iteration count - physx_scene_api.CreateMinVelocityIterationCountAttr(self.cfg.physx.min_velocity_iteration_count) - physx_scene_api.CreateMaxVelocityIterationCountAttr(self.cfg.physx.max_velocity_iteration_count) - - # create the default physics material - # this material is used when no material is specified for a primitive - # check: https://isaac-sim.github.io/IsaacLab/main/source/api/lab/isaaclab.sim.html#isaaclab.sim.SimulationCfg.physics_material - material_path = f"{self.cfg.physics_prim_path}/defaultMaterial" - self.cfg.physics_material.func(material_path, self.cfg.physics_material) - # bind the physics material to the scene - bind_physics_material(self.cfg.physics_prim_path, material_path) - - def _load_fabric_interface(self): - """Loads the fabric interface if enabled.""" - if self.cfg.use_fabric: - from omni.physxfabric import get_physx_fabric_interface - - # acquire fabric interface - self._fabric_iface = get_physx_fabric_interface() - if hasattr(self._fabric_iface, "force_update"): - # The update method in the fabric interface only performs an update if a physics step has occurred. - # However, for rendering, we need to force an update since any element of the scene might have been - # modified in a reset (which occurs after the physics step) and we want the renderer to be aware of - # these changes. - self._update_fabric = self._fabric_iface.force_update - else: - # Needed for backward compatibility with older Isaac Sim versions - self._update_fabric = self._fabric_iface.update - - def _update_anim_recording(self): - """Tracks anim recording timestamps and triggers finish animation recording if the total time has elapsed.""" - if self._anim_recording_started_timestamp is None: - self._anim_recording_started_timestamp = time.time() - - if self._anim_recording_started_timestamp is not None: - anim_recording_total_time = time.time() - self._anim_recording_started_timestamp - if anim_recording_total_time > self._anim_recording_stop_time: - self._finish_anim_recording() - return True - return False - - def _setup_anim_recording(self): - """Sets up anim recording settings and initializes the recording.""" - - self._anim_recording_enabled = bool(self.carb_settings.get("/isaaclab/anim_recording/enabled")) - if not self._anim_recording_enabled: - return + # Clear thread-local stage context + if hasattr(stage_utils._context, "stage"): + delattr(stage_utils._context, "stage") - # Import omni.physx.pvd.bindings here since it is not available by default - from omni.physxpvd.bindings import _physxPvd - - # Init anim recording settings - self._anim_recording_start_time = self.carb_settings.get("/isaaclab/anim_recording/start_time") - self._anim_recording_stop_time = self.carb_settings.get("/isaaclab/anim_recording/stop_time") - self._anim_recording_first_step_timestamp = None - self._anim_recording_started_timestamp = None - - # Make output path relative to repo path - repo_path = os.path.join(carb.tokens.get_tokens_interface().resolve("${app}"), "..") - self._anim_recording_timestamp = datetime.now().strftime("%Y_%m_%d_%H%M%S") - self._anim_recording_output_dir = ( - os.path.join(repo_path, "anim_recordings", self._anim_recording_timestamp).replace("\\", "/").rstrip("/") - + "/" - ) - os.makedirs(self._anim_recording_output_dir, exist_ok=True) - - # Acquire physx pvd interface and set output directory - self._physxPvdInterface = _physxPvd.acquire_physx_pvd_interface() - - # Set carb settings for the output path and enabling pvd recording - self.carb_settings.set_string( - "/persistent/physics/omniPvdOvdRecordingDirectory", self._anim_recording_output_dir - ) - self.carb_settings.set_bool("/physics/omniPvdOutputEnabled", True) - - def _update_usda_start_time(self, file_path, start_time): - """Updates the start time of the USDA baked anim recordingfile.""" - - # Read the USDA file - with open(file_path) as file: - content = file.read() - - # Extract the timeCodesPerSecond value - time_code_match = re.search(r"timeCodesPerSecond\s*=\s*(\d+)", content) - if not time_code_match: - raise ValueError("timeCodesPerSecond not found in the file.") - time_codes_per_second = int(time_code_match.group(1)) - - # Compute the new start time code - new_start_time_code = int(start_time * time_codes_per_second) - - # Replace the startTimeCode in the file - content = re.sub(r"startTimeCode\s*=\s*\d+", f"startTimeCode = {new_start_time_code}", content) - - # Write the updated content back to the file - with open(file_path, "w") as file: - file.write(content) - - def _finish_anim_recording(self): - """Finishes the animation recording and outputs the baked animation recording.""" - - logger.warning( - "[INFO][SimulationContext]: Finishing animation recording. Stage must be saved. Might take a few minutes." - ) - - # Detaching the stage will also close it and force the serialization of the OVD file - physx = omni.physx.get_physx_simulation_interface() - physx.detach_stage() - - # Save stage to disk - stage_path = os.path.join(self._anim_recording_output_dir, "stage_simulation.usdc") - sim_utils.save_stage(stage_path, save_and_reload_in_place=False) - - # Find the latest ovd file not named tmp.ovd - ovd_files = [ - f for f in glob.glob(os.path.join(self._anim_recording_output_dir, "*.ovd")) if not f.endswith("tmp.ovd") - ] - input_ovd_path = max(ovd_files, key=os.path.getctime) - - # Invoke pvd interface to create recording - stage_filename = "baked_animation_recording.usda" - result = self._physxPvdInterface.ovd_to_usd_over_with_layer_creation( - input_ovd_path, - stage_path, - self._anim_recording_output_dir, - stage_filename, - self._anim_recording_start_time, - self._anim_recording_stop_time, - True, # True: ASCII layers / False : USDC layers - False, # True: verify over layer - ) - - # Workaround for manually setting the truncated start time in the baked animation recording - self._update_usda_start_time( - os.path.join(self._anim_recording_output_dir, stage_filename), self._anim_recording_start_time - ) - - # Disable recording - self.carb_settings.set_bool("/physics/omniPvdOutputEnabled", False) - - return result + # Clear instance + cls._instance = None - """ - Callbacks. - """ + gc.collect() + logger.info("SimulationContext cleared") - def _app_control_on_stop_handle_fn(self, event: carb.events.IEvent): - """Callback to deal with the app when the simulation is stopped. - - Once the simulation is stopped, the physics handles go invalid. After that, it is not possible to - resume the simulation from the last state. This leaves the app in an inconsistent state, where - two possible actions can be taken: + @classmethod + def clear_stage(cls) -> None: + """Clear the current USD stage (preserving /World and PhysicsScene).""" + if cls._instance is None: + return - 1. **Keep the app rendering**: In this case, the simulation is kept running and the app is not shutdown. - However, the physics is not updated and the script cannot be resumed from the last state. The - user has to manually close the app to stop the simulation. - 2. **Shutdown the app**: This is the default behavior. In this case, the app is shutdown and - the simulation is stopped. + def _predicate(prim: Usd.Prim) -> bool: + path = prim.GetPath().pathString # type: ignore[union-attr] + return path != "/World" and prim.GetTypeName() != "PhysicsScene" - Note: - This callback is used only when running the simulation in a standalone python script. In an extension, - it is expected that the user handles the extension shutdown. - """ - if not self._disable_app_control_on_stop_handle: - while not omni.timeline.get_timeline_interface().is_playing(): - self.render() - return + sim_utils.clear_stage(predicate=_predicate) @contextmanager @@ -1054,91 +346,48 @@ def build_simulation_context( ) -> Iterator[SimulationContext]: """Context manager to build a simulation context with the provided settings. - This function facilitates the creation of a simulation context and provides flexibility in configuring various - aspects of the simulation, such as time step, gravity, device, and scene elements like ground plane and - lighting. - - If :attr:`sim_cfg` is None, then an instance of :class:`SimulationCfg` is created with default settings, - with parameters overwritten based on arguments to the function. - - An example usage of the context manager function: - - .. code-block:: python - - with build_simulation_context() as sim: - # Design the scene - - # Play the simulation - sim.reset() - while sim.is_playing(): - sim.step() - Args: create_new_stage: Whether to create a new stage. Defaults to True. - gravity_enabled: Whether to enable gravity in the simulation. Defaults to True. + gravity_enabled: Whether to enable gravity. Defaults to True. device: Device to run the simulation on. Defaults to "cuda:0". - dt: Time step for the simulation: Defaults to 0.01. - sim_cfg: :class:`isaaclab.sim.SimulationCfg` to use for the simulation. Defaults to None. - add_ground_plane: Whether to add a ground plane to the simulation. Defaults to False. - add_lighting: Whether to add a dome light to the simulation. Defaults to False. - auto_add_lighting: Whether to automatically add a dome light to the simulation if the simulation has a GUI. - Defaults to False. This is useful for debugging tests in the GUI. + dt: Time step for the simulation. Defaults to 0.01. + sim_cfg: SimulationCfg to use. Defaults to None. + add_ground_plane: Whether to add a ground plane. Defaults to False. + add_lighting: Whether to add a dome light. Defaults to False. + auto_add_lighting: Whether to auto-add lighting if GUI present. Defaults to False. Yields: The simulation context to use for the simulation. - """ try: if create_new_stage: - sim_utils.create_new_stage() + stage_utils.create_new_stage() if sim_cfg is None: - # Construct one and overwrite the dt, gravity, and device - sim_cfg = SimulationCfg(dt=dt) - - # Set up gravity - if gravity_enabled: - sim_cfg.gravity = (0.0, 0.0, -9.81) - else: - sim_cfg.gravity = (0.0, 0.0, 0.0) + from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg - # Set device - sim_cfg.device = device + gravity = (0.0, 0.0, -9.81) if gravity_enabled else (0.0, 0.0, 0.0) + physics_manager_cfg = PhysxManagerCfg(dt=dt, device=device, gravity=gravity) + sim_cfg = SimulationCfg(physics_manager_cfg=physics_manager_cfg) - # Construct simulation context sim = SimulationContext(sim_cfg) if add_ground_plane: - # Ground-plane cfg = GroundPlaneCfg() cfg.func("/World/defaultGroundPlane", cfg) - if add_lighting or (auto_add_lighting and sim.has_gui()): - # Lighting + if add_lighting or (auto_add_lighting and sim.get_setting("/isaaclab/has_gui")): cfg = DomeLightCfg( - color=(0.1, 0.1, 0.1), - enable_color_temperature=True, - color_temperature=5500, - intensity=10000, + color=(0.1, 0.1, 0.1), enable_color_temperature=True, color_temperature=5500, intensity=10000 ) - # Dome light named specifically to avoid conflicts cfg.func(prim_path="/World/defaultDomeLight", cfg=cfg, translation=(0.0, 0.0, 10.0)) yield sim except Exception: - sim.logger.error(traceback.format_exc()) + logger.error(traceback.format_exc()) raise finally: - if not sim.has_gui(): - # Stop simulation only if we aren't rendering otherwise the app will hang indefinitely + if not sim.get_setting("/isaaclab/has_gui"): sim.stop() - - # Clear the stage - sim.clear_all_callbacks() sim.clear_instance() - # check if we need to raise an exception that was raised in a callback - if builtins.ISAACLAB_CALLBACK_EXCEPTION is not None: - exception_to_raise = builtins.ISAACLAB_CALLBACK_EXCEPTION - builtins.ISAACLAB_CALLBACK_EXCEPTION = None - raise exception_to_raise diff --git a/source/isaaclab/isaaclab/visualizers/__init__.py b/source/isaaclab/isaaclab/visualizers/__init__.py new file mode 100644 index 00000000000..daa193999c4 --- /dev/null +++ b/source/isaaclab/isaaclab/visualizers/__init__.py @@ -0,0 +1,27 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +# Visualizer Registry +# ------------------- +# This module uses a registry pattern to decouple visualizer instantiation from specific types. +# Visualizer implementations can register themselves using the `register_visualizer` decorator, +# and configs can create visualizers via the `create_visualizer()` factory method. +# """ + +from __future__ import annotations + +from typing import Any + +# Import base classes first +from .visualizer import Visualizer +from .visualizer_cfg import VisualizerCfg + +# Global registry for visualizer types (lazy-loaded) +_VISUALIZER_REGISTRY: dict[str, Any] = {} + +__all__ = [ + "Visualizer", + "VisualizerCfg", +] diff --git a/source/isaaclab/isaaclab/visualizers/visualizer.py b/source/isaaclab/isaaclab/visualizers/visualizer.py new file mode 100644 index 00000000000..79d3bf3606d --- /dev/null +++ b/source/isaaclab/isaaclab/visualizers/visualizer.py @@ -0,0 +1,107 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Base class for visualizers.""" + +from __future__ import annotations + +from abc import ABC, abstractmethod +from typing import TYPE_CHECKING, Any + +if TYPE_CHECKING: + from .visualizer_cfg import VisualizerCfg + + +class Visualizer(ABC): + """Base class for all visualizer backends. + + Lifecycle: __init__() -> initialize() -> step() (repeated) -> close() + """ + + def __init__(self, cfg: VisualizerCfg): + """Initialize visualizer with config.""" + self.cfg = cfg + self._is_initialized = False + self._is_closed = False + + @abstractmethod + def initialize(self, scene_data: dict[str, Any] | None = None) -> None: + """Initialize visualizer with scene data (model, state, usd_stage, etc.).""" + pass + + @abstractmethod + def step(self, dt: float, state: Any | None = None) -> None: + """Update visualization for one step. + + Args: + dt: Time step in seconds. + state: Updated physics state (e.g., newton.State). + """ + pass + + @abstractmethod + def close(self) -> None: + """Clean up resources.""" + pass + + @abstractmethod + def is_running(self) -> bool: + """Check if visualizer is still running (e.g., window not closed).""" + pass + + @abstractmethod + def is_stopped(self) -> bool: + """Check if visualizer is stopped (e.g., window closed).""" + pass + + def is_training_paused(self) -> bool: + """Check if training is paused by visualizer controls.""" + return False + + def is_rendering_paused(self) -> bool: + """Check if rendering is paused by visualizer controls.""" + return False + + @property + def is_initialized(self) -> bool: + """Check if initialize() has been called.""" + return self._is_initialized + + @property + def is_closed(self) -> bool: + """Check if close() has been called.""" + return self._is_closed + + def supports_markers(self) -> bool: + """Check if visualizer supports VisualizationMarkers.""" + return False + + def supports_live_plots(self) -> bool: + """Check if visualizer supports LivePlots.""" + return False + + def get_rendering_dt(self) -> float | None: + """Get rendering time step. Returns None to use interface default.""" + return None + + def set_camera_view(self, eye: tuple, target: tuple) -> None: + """Set camera view position. No-op by default.""" + pass + + def reset(self, soft: bool = False) -> None: + """Reset visualizer state. No-op by default.""" + pass + + def play(self) -> None: + """Handle simulation play/start. No-op by default.""" + pass + + def pause(self) -> None: + """Handle simulation pause. No-op by default.""" + pass + + def stop(self) -> None: + """Handle simulation stop. No-op by default.""" + pass diff --git a/source/isaaclab/isaaclab/visualizers/visualizer_cfg.py b/source/isaaclab/isaaclab/visualizers/visualizer_cfg.py new file mode 100644 index 00000000000..370d1ad94e1 --- /dev/null +++ b/source/isaaclab/isaaclab/visualizers/visualizer_cfg.py @@ -0,0 +1,82 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Base configuration for visualizers.""" + +from __future__ import annotations + +from typing import TYPE_CHECKING + +from isaaclab.utils import configclass + +if TYPE_CHECKING: + from .visualizer import Visualizer + + +@configclass +class VisualizerCfg: + """Base configuration for all visualizer backends. + + Note: + This is an abstract base class and should not be instantiated directly. + Use specific visualizer configs like NewtonVisualizerCfg, RerunVisualizerCfg, or OVVisualizerCfg. + """ + + visualizer_type: str | None = None + """Type identifier (e.g., 'newton', 'rerun', 'omniverse'). Must be overridden by subclasses.""" + + # Note: Partial environment visualization will come later + # env_ids: list[Integer] = [] + + enable_markers: bool = True + """Enable visualization markers (debug drawing).""" + + enable_live_plots: bool = True + """Enable live plotting of data. + + When set to True for OVVisualizer: + - Automatically checks the checkboxes for all manager visualizers (Actions, Observations, Rewards, etc.) + - Keeps the plot frames expanded by default (not collapsed) + - Makes the live plots visible immediately in the IsaacLab window (docked to the right of the viewport) + + This provides a better out-of-the-box experience when you want to monitor training metrics. + """ + + camera_position: tuple[float, float, float] = (8.0, 8.0, 3.0) + """Initial camera position (x, y, z) in world coordinates.""" + + camera_target: tuple[float, float, float] = (0.0, 0.0, 0.0) + """Initial camera target/look-at point (x, y, z) in world coordinates.""" + + def get_visualizer_type(self) -> str | None: + """Get the visualizer type identifier. + + Returns: + The visualizer type string, or None if not set (base class). + """ + return self.visualizer_type + + def create_visualizer(self) -> Visualizer: + """Create visualizer instance from this config using factory pattern. + + Raises: + ValueError: If visualizer_type is None (base class used directly) or not registered. + """ + from . import get_visualizer_class + + if self.visualizer_type is None: + raise ValueError( + "Cannot create visualizer from base VisualizerCfg class. " + "Use a specific visualizer config: NewtonVisualizerCfg, RerunVisualizerCfg, or OVVisualizerCfg." + ) + + visualizer_class = get_visualizer_class(self.visualizer_type) + if visualizer_class is None: + raise ValueError( + f"Visualizer type '{self.visualizer_type}' is not registered. " + "Valid types: 'newton', 'rerun', 'omniverse'." + ) + + return visualizer_class(self) diff --git a/source/isaaclab/test/app/test_non_headless_launch.py b/source/isaaclab/test/app/test_non_headless_launch.py index eb8544b995c..9c4df46eca6 100644 --- a/source/isaaclab/test/app/test_non_headless_launch.py +++ b/source/isaaclab/test/app/test_non_headless_launch.py @@ -22,6 +22,7 @@ import isaaclab.sim as sim_utils from isaaclab.assets import AssetBaseCfg +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.scene import InteractiveScene, InteractiveSceneCfg from isaaclab.utils import configclass @@ -51,7 +52,7 @@ def run_simulator( @pytest.mark.isaacsim_ci def test_non_headless_launch(): # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(dt=0.005) + sim_cfg = sim_utils.SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.005)) sim = sim_utils.SimulationContext(sim_cfg) # design scene scene_cfg = SensorsSceneCfg(num_envs=1, env_spacing=2.0) diff --git a/source/isaaclab/test/assets/check_external_force.py b/source/isaaclab/test/assets/check_external_force.py index f038b907a1f..8f0f7a29a11 100644 --- a/source/isaaclab/test/assets/check_external_force.py +++ b/source/isaaclab/test/assets/check_external_force.py @@ -40,6 +40,7 @@ import isaaclab.sim as sim_utils from isaaclab.assets import Articulation +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sim import SimulationContext ## @@ -52,7 +53,7 @@ def main(): """Main function.""" # Load kit helper - sim = SimulationContext(sim_utils.SimulationCfg(dt=0.005)) + sim = SimulationContext(sim_utils.SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.005))) # Set main camera sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) diff --git a/source/isaaclab/test/assets/check_fixed_base_assets.py b/source/isaaclab/test/assets/check_fixed_base_assets.py index c62c5a3334d..454e67fe429 100644 --- a/source/isaaclab/test/assets/check_fixed_base_assets.py +++ b/source/isaaclab/test/assets/check_fixed_base_assets.py @@ -37,6 +37,7 @@ import isaaclab.sim as sim_utils from isaaclab.assets import Articulation +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg ## # Pre-defined configs @@ -143,7 +144,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim = sim_utils.SimulationContext(sim_utils.SimulationCfg(dt=0.01)) + sim = sim_utils.SimulationContext(sim_utils.SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01))) # Set main camera sim.set_camera_view(eye=[2.5, 2.5, 2.5], target=[0.0, 0.0, 0.0]) # design scene diff --git a/source/isaaclab/test/controllers/test_differential_ik.py b/source/isaaclab/test/controllers/test_differential_ik.py index 871676111ca..9e6ef349a1d 100644 --- a/source/isaaclab/test/controllers/test_differential_ik.py +++ b/source/isaaclab/test/controllers/test_differential_ik.py @@ -20,6 +20,7 @@ import isaaclab.sim as sim_utils from isaaclab.assets import Articulation from isaaclab.controllers import DifferentialIKController, DifferentialIKControllerCfg +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.utils.math import ( # isort:skip compute_pose_error, @@ -43,7 +44,7 @@ def sim(): # Constants num_envs = 1 # Load kit helper - sim_cfg = sim_utils.SimulationCfg(dt=0.01) + sim_cfg = sim_utils.SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01)) sim = sim_utils.SimulationContext(sim_cfg) # TODO: Remove this once we have a better way to handle this. sim._app_control_on_stop_handle = None diff --git a/source/isaaclab/test/controllers/test_operational_space.py b/source/isaaclab/test/controllers/test_operational_space.py index e1ad6be17ea..d424dc34b62 100644 --- a/source/isaaclab/test/controllers/test_operational_space.py +++ b/source/isaaclab/test/controllers/test_operational_space.py @@ -21,6 +21,7 @@ import isaaclab.sim as sim_utils from isaaclab.assets import Articulation from isaaclab.controllers import OperationalSpaceController, OperationalSpaceControllerCfg +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.markers import VisualizationMarkers from isaaclab.markers.config import FRAME_MARKER_CFG from isaaclab.sensors import ContactSensor, ContactSensorCfg @@ -48,7 +49,7 @@ def sim(): # Constants num_envs = 16 # Load kit helper - sim_cfg = sim_utils.SimulationCfg(dt=0.01) + sim_cfg = sim_utils.SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01)) sim = sim_utils.SimulationContext(sim_cfg) # TODO: Remove this once we have a better way to handle this. sim._app_control_on_stop_handle = None diff --git a/source/isaaclab/test/devices/check_keyboard.py b/source/isaaclab/test/devices/check_keyboard.py index c1a8b07bef8..0a6583936f4 100644 --- a/source/isaaclab/test/devices/check_keyboard.py +++ b/source/isaaclab/test/devices/check_keyboard.py @@ -24,6 +24,7 @@ import ctypes from isaaclab.devices import Se3Keyboard, Se3KeyboardCfg +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sim import SimulationCfg, SimulationContext @@ -40,7 +41,7 @@ def quit_cb(): def main(): # Load kit helper - sim = SimulationContext(SimulationCfg(dt=0.01)) + sim = SimulationContext(SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01))) # Create teleoperation interface teleop_interface = Se3Keyboard(Se3KeyboardCfg(pos_sensitivity=0.1, rot_sensitivity=0.1)) diff --git a/source/isaaclab/test/envs/test_env_rendering_logic.py b/source/isaaclab/test/envs/test_env_rendering_logic.py index 70f0a01f212..7ac437ae3c7 100644 --- a/source/isaaclab/test/envs/test_env_rendering_logic.py +++ b/source/isaaclab/test/envs/test_env_rendering_logic.py @@ -27,6 +27,7 @@ ManagerBasedRLEnvCfg, ) from isaaclab.scene import InteractiveSceneCfg +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sim import SimulationCfg, SimulationContext from isaaclab.utils import configclass @@ -47,7 +48,7 @@ class EnvCfg(ManagerBasedEnvCfg): decimation: int = 4 episode_length_s: float = 100.0 - sim: SimulationCfg = SimulationCfg(dt=0.005, render_interval=render_interval) + sim: SimulationCfg = SimulationCfg(render_interval=render_interval, physics_manager_cfg=PhysxManagerCfg(dt=0.005)) scene: InteractiveSceneCfg = InteractiveSceneCfg(num_envs=1, env_spacing=1.0) actions: EmptyManagerCfg = EmptyManagerCfg() observations: EmptyManagerCfg = EmptyManagerCfg() @@ -64,7 +65,7 @@ class EnvCfg(ManagerBasedRLEnvCfg): decimation: int = 4 episode_length_s: float = 100.0 - sim: SimulationCfg = SimulationCfg(dt=0.005, render_interval=render_interval) + sim: SimulationCfg = SimulationCfg(render_interval=render_interval, physics_manager_cfg=PhysxManagerCfg(dt=0.005)) scene: InteractiveSceneCfg = InteractiveSceneCfg(num_envs=1, env_spacing=1.0) actions: EmptyManagerCfg = EmptyManagerCfg() observations: EmptyManagerCfg = EmptyManagerCfg() @@ -85,7 +86,7 @@ class EnvCfg(DirectRLEnvCfg): action_space: int = 0 observation_space: int = 0 episode_length_s: float = 100.0 - sim: SimulationCfg = SimulationCfg(dt=0.005, render_interval=render_interval) + sim: SimulationCfg = SimulationCfg(render_interval=render_interval, physics_manager_cfg=PhysxManagerCfg(dt=0.005)) scene: InteractiveSceneCfg = InteractiveSceneCfg(num_envs=1, env_spacing=1.0) class Env(DirectRLEnv): diff --git a/source/isaaclab/test/managers/test_observation_manager.py b/source/isaaclab/test/managers/test_observation_manager.py index 86e77c571a4..4bb2f8a687c 100644 --- a/source/isaaclab/test/managers/test_observation_manager.py +++ b/source/isaaclab/test/managers/test_observation_manager.py @@ -22,6 +22,7 @@ import torch import isaaclab.sim as sim_utils +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.managers import ( ManagerTermBase, ObservationGroupCfg, @@ -107,7 +108,7 @@ def setup_env(): num_envs = 20 device = "cuda:0" # set up sim - sim_cfg = sim_utils.SimulationCfg(dt=dt, device=device) + sim_cfg = sim_utils.SimulationCfg(device=device, physics_manager_cfg=PhysxManagerCfg(dt=dt)) sim = sim_utils.SimulationContext(sim_cfg) # create dummy environment env = namedtuple("ManagerBasedEnv", ["num_envs", "device", "data", "dt", "sim"])( diff --git a/source/isaaclab/test/markers/check_markers_visibility.py b/source/isaaclab/test/markers/check_markers_visibility.py index 98dbee8ddcd..27752d39da9 100644 --- a/source/isaaclab/test/markers/check_markers_visibility.py +++ b/source/isaaclab/test/markers/check_markers_visibility.py @@ -40,6 +40,7 @@ import isaaclab.sim as sim_utils from isaaclab.assets import ArticulationCfg, AssetBaseCfg +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.scene import InteractiveScene, InteractiveSceneCfg from isaaclab.sensors import RayCasterCfg, patterns from isaaclab.utils import configclass @@ -129,7 +130,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(dt=0.005) + sim_cfg = sim_utils.SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.005)) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) diff --git a/source/isaaclab/test/markers/test_visualization_markers.py b/source/isaaclab/test/markers/test_visualization_markers.py index ebc183b804b..cc8fe7cba35 100644 --- a/source/isaaclab/test/markers/test_visualization_markers.py +++ b/source/isaaclab/test/markers/test_visualization_markers.py @@ -18,6 +18,7 @@ import isaaclab.sim as sim_utils from isaaclab.markers import VisualizationMarkers, VisualizationMarkersCfg from isaaclab.markers.config import FRAME_MARKER_CFG, POSITION_GOAL_MARKER_CFG +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sim import SimulationCfg, SimulationContext from isaaclab.utils.math import random_orientation from isaaclab.utils.timer import Timer @@ -31,7 +32,7 @@ def sim(): # Open a new stage sim_utils.create_new_stage() # Load kit helper - sim_context = SimulationContext(SimulationCfg(dt=dt)) + sim_context = SimulationContext(SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=dt))) yield sim_context # Cleanup sim_context._disable_app_control_on_stop_handle = True # prevent timeout diff --git a/source/isaaclab/test/scene/check_interactive_scene.py b/source/isaaclab/test/scene/check_interactive_scene.py index 5b2463b315a..8f4f609e752 100644 --- a/source/isaaclab/test/scene/check_interactive_scene.py +++ b/source/isaaclab/test/scene/check_interactive_scene.py @@ -29,6 +29,7 @@ import isaaclab.sim as sim_utils from isaaclab.assets import AssetBaseCfg +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.scene import InteractiveScene, InteractiveSceneCfg from isaaclab.sensors.ray_caster import RayCasterCfg, patterns from isaaclab.sim import SimulationContext @@ -80,7 +81,7 @@ def main(): """Main function.""" # Load kit helper - sim = SimulationContext(sim_utils.SimulationCfg(dt=0.005)) + sim = SimulationContext(sim_utils.SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.005))) # Set main camera sim.set_camera_view(eye=[5, 5, 5], target=[0.0, 0.0, 0.0]) diff --git a/source/isaaclab/test/sensors/test_camera.py b/source/isaaclab/test/sensors/test_camera.py index e73d572a0ff..a0f2a103303 100644 --- a/source/isaaclab/test/sensors/test_camera.py +++ b/source/isaaclab/test/sensors/test_camera.py @@ -29,6 +29,7 @@ from pxr import Gf, Usd, UsdGeom import isaaclab.sim as sim_utils +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sensors.camera import Camera, CameraCfg from isaaclab.utils import convert_dict_to_backend from isaaclab.utils.timer import Timer @@ -63,7 +64,7 @@ def setup() -> tuple[sim_utils.SimulationContext, CameraCfg, float]: # Simulation time-step dt = 0.01 # Load kit helper - sim_cfg = sim_utils.SimulationCfg(dt=dt) + sim_cfg = sim_utils.SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=dt)) sim = sim_utils.SimulationContext(sim_cfg) # populate scene _populate_scene() diff --git a/source/isaaclab/test/sensors/test_multi_mesh_ray_caster_camera.py b/source/isaaclab/test/sensors/test_multi_mesh_ray_caster_camera.py index 46b14c5129b..f738727458d 100644 --- a/source/isaaclab/test/sensors/test_multi_mesh_ray_caster_camera.py +++ b/source/isaaclab/test/sensors/test_multi_mesh_ray_caster_camera.py @@ -26,6 +26,7 @@ from pxr import Gf import isaaclab.sim as sim_utils +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sensors.camera import Camera, CameraCfg from isaaclab.sensors.ray_caster import MultiMeshRayCasterCamera, MultiMeshRayCasterCameraCfg, patterns from isaaclab.sim import PinholeCameraCfg @@ -49,7 +50,7 @@ def setup_simulation(): # Simulation time-step dt = 0.01 # Load kit helper - sim_cfg = sim_utils.SimulationCfg(dt=dt) + sim_cfg = sim_utils.SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=dt)) sim: sim_utils.SimulationContext = sim_utils.SimulationContext(sim_cfg) # Ground-plane mesh = make_plane(size=(100, 100), height=0.0, center_zero=True) diff --git a/source/isaaclab/test/sensors/test_multi_tiled_camera.py b/source/isaaclab/test/sensors/test_multi_tiled_camera.py index 85ffc88c6a1..b9753193b18 100644 --- a/source/isaaclab/test/sensors/test_multi_tiled_camera.py +++ b/source/isaaclab/test/sensors/test_multi_tiled_camera.py @@ -28,6 +28,7 @@ from pxr import Gf, UsdGeom import isaaclab.sim as sim_utils +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sensors.camera import TiledCamera, TiledCameraCfg @@ -50,7 +51,7 @@ def setup_camera(): # Simulation time-step dt = 0.01 # Load kit helper - sim_cfg = sim_utils.SimulationCfg(dt=dt) + sim_cfg = sim_utils.SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=dt)) sim = sim_utils.SimulationContext(sim_cfg) # populate scene _populate_scene() diff --git a/source/isaaclab/test/sensors/test_ray_caster_camera.py b/source/isaaclab/test/sensors/test_ray_caster_camera.py index 08f02fb7e50..3d925880e5c 100644 --- a/source/isaaclab/test/sensors/test_ray_caster_camera.py +++ b/source/isaaclab/test/sensors/test_ray_caster_camera.py @@ -26,6 +26,7 @@ from pxr import Gf import isaaclab.sim as sim_utils +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sensors.camera import Camera, CameraCfg from isaaclab.sensors.ray_caster import RayCasterCamera, RayCasterCameraCfg, patterns from isaaclab.sim import PinholeCameraCfg @@ -69,7 +70,7 @@ def setup() -> tuple[sim_utils.SimulationContext, RayCasterCameraCfg, float]: # Simulation time-step dt = 0.01 # Load kit helper - sim_cfg = sim_utils.SimulationCfg(dt=dt) + sim_cfg = sim_utils.SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=dt)) sim = sim_utils.SimulationContext(sim_cfg) # Ground-plane mesh = make_plane(size=(100, 100), height=0.0, center_zero=True) diff --git a/source/isaaclab/test/sensors/test_sensor_base.py b/source/isaaclab/test/sensors/test_sensor_base.py index 1f41ba4ab4e..244979caa29 100644 --- a/source/isaaclab/test/sensors/test_sensor_base.py +++ b/source/isaaclab/test/sensors/test_sensor_base.py @@ -21,6 +21,7 @@ import torch import isaaclab.sim as sim_utils +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sensors import SensorBase, SensorBaseCfg from isaaclab.utils import configclass @@ -93,7 +94,7 @@ def create_dummy_sensor(request, device): # Simulation time-step dt = 0.01 # Load kit helper - sim_cfg = sim_utils.SimulationCfg(dt=dt, device=device) + sim_cfg = sim_utils.SimulationCfg(device=device, physics_manager_cfg=PhysxManagerCfg(dt=dt)) sim = sim_utils.SimulationContext(sim_cfg) # create sensor diff --git a/source/isaaclab/test/sensors/test_tiled_camera.py b/source/isaaclab/test/sensors/test_tiled_camera.py index 02fb0d24974..08866777c28 100644 --- a/source/isaaclab/test/sensors/test_tiled_camera.py +++ b/source/isaaclab/test/sensors/test_tiled_camera.py @@ -27,6 +27,7 @@ from pxr import Gf, UsdGeom import isaaclab.sim as sim_utils +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sensors.camera import Camera, CameraCfg, TiledCamera, TiledCameraCfg from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR from isaaclab.utils.timer import Timer @@ -51,7 +52,7 @@ def setup_camera(device) -> tuple[sim_utils.SimulationContext, TiledCameraCfg, f # Simulation time-step dt = 0.01 # Load kit helper - sim_cfg = sim_utils.SimulationCfg(dt=dt, device=device) + sim_cfg = sim_utils.SimulationCfg(device=device, physics_manager_cfg=PhysxManagerCfg(dt=dt)) sim: sim_utils.SimulationContext = sim_utils.SimulationContext(sim_cfg) # populate scene _populate_scene() diff --git a/source/isaaclab/test/sim/check_meshes.py b/source/isaaclab/test/sim/check_meshes.py index 705677281d3..121697f8eee 100644 --- a/source/isaaclab/test/sim/check_meshes.py +++ b/source/isaaclab/test/sim/check_meshes.py @@ -42,6 +42,7 @@ import tqdm import isaaclab.sim as sim_utils +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg def define_origins(num_origins: int, spacing: float) -> list[list[float]]: @@ -141,7 +142,7 @@ def design_scene(): def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(dt=0.01) + sim_cfg = sim_utils.SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01)) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view([8.0, 8.0, 6.0], [0.0, 0.0, 0.0]) diff --git a/source/isaaclab/test/sim/test_mesh_converter.py b/source/isaaclab/test/sim/test_mesh_converter.py index 6678a994a1b..fedf35a409a 100644 --- a/source/isaaclab/test/sim/test_mesh_converter.py +++ b/source/isaaclab/test/sim/test_mesh_converter.py @@ -23,6 +23,7 @@ from pxr import UsdGeom, UsdPhysics import isaaclab.sim as sim_utils +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sim import SimulationCfg, SimulationContext from isaaclab.sim.converters import MeshConverter, MeshConverterCfg from isaaclab.sim.schemas import MESH_APPROXIMATION_TOKENS, schemas_cfg @@ -66,7 +67,7 @@ def sim(): # Simulation time-step dt = 0.01 # Load kit helper - sim = SimulationContext(SimulationCfg(dt=dt)) + sim = SimulationContext(SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=dt))) yield sim # stop simulation sim.stop() diff --git a/source/isaaclab/test/sim/test_mjcf_converter.py b/source/isaaclab/test/sim/test_mjcf_converter.py index 8ce098b4a51..d78aee7ef39 100644 --- a/source/isaaclab/test/sim/test_mjcf_converter.py +++ b/source/isaaclab/test/sim/test_mjcf_converter.py @@ -19,6 +19,7 @@ from isaacsim.core.utils.extensions import enable_extension, get_extension_path_from_name import isaaclab.sim as sim_utils +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sim import SimulationCfg, SimulationContext from isaaclab.sim.converters import MjcfConverter, MjcfConverterCfg @@ -31,7 +32,7 @@ def test_setup_teardown(): # Setup: Create simulation context dt = 0.01 - sim = SimulationContext(SimulationCfg(dt=dt)) + sim = SimulationContext(SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=dt))) # Setup: Create MJCF config enable_extension("isaacsim.asset.importer.mjcf") diff --git a/source/isaaclab/test/sim/test_schemas.py b/source/isaaclab/test/sim/test_schemas.py index 05710bd9228..40aecd369b6 100644 --- a/source/isaaclab/test/sim/test_schemas.py +++ b/source/isaaclab/test/sim/test_schemas.py @@ -20,6 +20,7 @@ import isaaclab.sim as sim_utils import isaaclab.sim.schemas as schemas +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sim import SimulationCfg, SimulationContext from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR from isaaclab.utils.string import to_camel_case @@ -33,7 +34,7 @@ def setup_simulation(): # Simulation time-step dt = 0.1 # Load kit helper - sim = SimulationContext(SimulationCfg(dt=dt)) + sim = SimulationContext(SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=dt))) # 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 4244b36ff8e..55d220cb418 100644 --- a/source/isaaclab/test/sim/test_simulation_context.py +++ b/source/isaaclab/test/sim/test_simulation_context.py @@ -20,6 +20,7 @@ import omni.physx import isaaclab.sim as sim_utils +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sim import SimulationCfg, SimulationContext diff --git a/source/isaaclab/test/sim/test_simulation_stage_in_memory.py b/source/isaaclab/test/sim/test_simulation_stage_in_memory.py index 68d9d86c666..82dc2087e80 100644 --- a/source/isaaclab/test/sim/test_simulation_stage_in_memory.py +++ b/source/isaaclab/test/sim/test_simulation_stage_in_memory.py @@ -60,7 +60,7 @@ def test_stage_in_memory_with_shapes(sim): num_clones = 10 # grab stage in memory and set as current stage via the with statement - stage_in_memory = sim.get_initial_stage() + stage_in_memory = sim.stage with sim_utils.use_stage(stage_in_memory): # create cloned cone stage for i in range(num_clones): @@ -151,7 +151,7 @@ def test_stage_in_memory_with_usds(sim): ] # grab stage in memory and set as current stage via the with statement - stage_in_memory = sim.get_initial_stage() + stage_in_memory = sim.stage with sim_utils.use_stage(stage_in_memory): # create cloned robot stage for i in range(num_clones): @@ -213,7 +213,7 @@ def test_stage_in_memory_with_clone_in_fabric(sim): num_clones = 100 # grab stage in memory and set as current stage via the with statement - stage_in_memory = sim.get_initial_stage() + stage_in_memory = sim.stage with sim_utils.use_stage(stage_in_memory): # set up paths base_env_path = "/World/envs" diff --git a/source/isaaclab/test/sim/test_spawn_from_files.py b/source/isaaclab/test/sim/test_spawn_from_files.py index cc6f2b3e536..2fd42661b8f 100644 --- a/source/isaaclab/test/sim/test_spawn_from_files.py +++ b/source/isaaclab/test/sim/test_spawn_from_files.py @@ -18,6 +18,7 @@ import omni.kit.app import isaaclab.sim as sim_utils +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sim import SimulationCfg, SimulationContext from isaaclab.utils.assets import ISAACLAB_NUCLEUS_DIR from isaaclab.utils.version import get_isaac_sim_version @@ -31,7 +32,7 @@ def sim(): # Simulation time-step dt = 0.1 # Load kit helper - sim = SimulationContext(SimulationCfg(dt=dt)) + sim = SimulationContext(SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=dt))) # Wait for spawning sim_utils.update_stage() diff --git a/source/isaaclab/test/sim/test_spawn_lights.py b/source/isaaclab/test/sim/test_spawn_lights.py index 9dbbd98cf7a..86d5c8262c4 100644 --- a/source/isaaclab/test/sim/test_spawn_lights.py +++ b/source/isaaclab/test/sim/test_spawn_lights.py @@ -18,6 +18,7 @@ from pxr import Usd, UsdLux import isaaclab.sim as sim_utils +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sim import SimulationCfg, SimulationContext from isaaclab.utils.string import to_camel_case @@ -30,7 +31,7 @@ def sim(): # Simulation time-step dt = 0.1 # Load kit helper - sim = SimulationContext(SimulationCfg(dt=dt)) + sim = SimulationContext(SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=dt))) # Wait for spawning sim_utils.update_stage() diff --git a/source/isaaclab/test/sim/test_spawn_materials.py b/source/isaaclab/test/sim/test_spawn_materials.py index e5c3b14f50d..1e34375c596 100644 --- a/source/isaaclab/test/sim/test_spawn_materials.py +++ b/source/isaaclab/test/sim/test_spawn_materials.py @@ -18,6 +18,7 @@ from pxr import UsdPhysics, UsdShade import isaaclab.sim as sim_utils +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sim import SimulationCfg, SimulationContext from isaaclab.utils.assets import NVIDIA_NUCLEUS_DIR @@ -27,7 +28,7 @@ def sim(): """Create a simulation context.""" sim_utils.create_new_stage() dt = 0.1 - sim = SimulationContext(SimulationCfg(dt=dt)) + sim = SimulationContext(SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=dt))) sim_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 43fbc7852c2..8ef59156789 100644 --- a/source/isaaclab/test/sim/test_spawn_meshes.py +++ b/source/isaaclab/test/sim/test_spawn_meshes.py @@ -16,6 +16,7 @@ import pytest import isaaclab.sim as sim_utils +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sim import SimulationCfg, SimulationContext @@ -27,7 +28,7 @@ def sim(): # Simulation time-step dt = 0.1 # Load kit helper - sim = SimulationContext(SimulationCfg(dt=dt)) + sim = SimulationContext(SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=dt))) # Wait for spawning sim_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 63f29af7830..44571c095df 100644 --- a/source/isaaclab/test/sim/test_spawn_sensors.py +++ b/source/isaaclab/test/sim/test_spawn_sensors.py @@ -18,6 +18,7 @@ from pxr import Usd import isaaclab.sim as sim_utils +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sim import SimulationCfg, SimulationContext from isaaclab.sim.spawners.sensors.sensors import CUSTOM_FISHEYE_CAMERA_ATTRIBUTES, CUSTOM_PINHOLE_CAMERA_ATTRIBUTES from isaaclab.utils.string import to_camel_case @@ -28,7 +29,7 @@ def sim(): """Create a simulation context.""" sim_utils.create_new_stage() dt = 0.1 - sim = SimulationContext(SimulationCfg(dt=dt)) + sim = SimulationContext(SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=dt))) sim_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 4c18753d52e..525725960de 100644 --- a/source/isaaclab/test/sim/test_spawn_shapes.py +++ b/source/isaaclab/test/sim/test_spawn_shapes.py @@ -15,6 +15,7 @@ import pytest import isaaclab.sim as sim_utils +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sim import SimulationCfg, SimulationContext @@ -23,7 +24,7 @@ def sim(): """Create a simulation context.""" sim_utils.create_new_stage() dt = 0.1 - sim = SimulationContext(SimulationCfg(dt=dt)) + sim = SimulationContext(SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=dt))) sim_utils.update_stage() yield sim sim._disable_app_control_on_stop_handle = True # prevent timeout diff --git a/source/isaaclab/test/sim/test_spawn_wrappers.py b/source/isaaclab/test/sim/test_spawn_wrappers.py index 1571bb62bdc..66bfa3c4dd8 100644 --- a/source/isaaclab/test/sim/test_spawn_wrappers.py +++ b/source/isaaclab/test/sim/test_spawn_wrappers.py @@ -16,6 +16,7 @@ import pytest import isaaclab.sim as sim_utils +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sim import SimulationCfg, SimulationContext from isaaclab.utils.assets import ISAACLAB_NUCLEUS_DIR @@ -25,7 +26,7 @@ def sim(): """Create a simulation context.""" sim_utils.create_new_stage() dt = 0.1 - sim = SimulationContext(SimulationCfg(dt=dt)) + sim = SimulationContext(SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=dt))) sim_utils.update_stage() yield sim sim.stop() diff --git a/source/isaaclab/test/sim/test_urdf_converter.py b/source/isaaclab/test/sim/test_urdf_converter.py index 52cb6d28792..4203d306d4f 100644 --- a/source/isaaclab/test/sim/test_urdf_converter.py +++ b/source/isaaclab/test/sim/test_urdf_converter.py @@ -22,6 +22,7 @@ from isaacsim.core.prims import Articulation import isaaclab.sim as sim_utils +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sim import SimulationCfg, SimulationContext from isaaclab.sim.converters import UrdfConverter, UrdfConverterCfg from isaaclab.utils.version import get_isaac_sim_version @@ -53,7 +54,7 @@ def sim_config(): # Simulation time-step dt = 0.01 # Load kit helper - sim = SimulationContext(SimulationCfg(dt=dt)) + sim = SimulationContext(SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=dt))) yield sim, config # Teardown sim._disable_app_control_on_stop_handle = True # prevent timeout diff --git a/source/isaaclab/test/sim/test_views_xform_prim.py b/source/isaaclab/test/sim/test_views_xform_prim.py index 1601ef303b7..43f31f52a27 100644 --- a/source/isaaclab/test/sim/test_views_xform_prim.py +++ b/source/isaaclab/test/sim/test_views_xform_prim.py @@ -21,6 +21,7 @@ _IsaacSimXformPrimView = None import isaaclab.sim as sim_utils # noqa: E402 +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg # noqa: E402 from isaaclab.sim.views import XformPrimView as XformPrimView # noqa: E402 from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR # noqa: E402 @@ -73,7 +74,7 @@ def _prim_type_for_backend(backend: str) -> str: def _create_view(pattern: str, device: str, backend: str) -> XformPrimView: """Create an XformPrimView for the requested backend.""" if backend == "fabric": - sim_utils.SimulationContext(sim_utils.SimulationCfg(dt=0.01, device=device, use_fabric=True)) + sim_utils.SimulationContext(sim_utils.SimulationCfg(device=device, physics_manager_cfg=PhysxManagerCfg(dt=0.01, use_fabric=True))) return XformPrimView(pattern, device=device) diff --git a/source/isaaclab/test/visualization/check_scene_xr_visualization.py b/source/isaaclab/test/visualization/check_scene_xr_visualization.py index b03fa9e88bd..d367d28c36a 100644 --- a/source/isaaclab/test/visualization/check_scene_xr_visualization.py +++ b/source/isaaclab/test/visualization/check_scene_xr_visualization.py @@ -41,6 +41,7 @@ import isaaclab.sim as sim_utils from isaaclab.assets import AssetBaseCfg +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.scene import InteractiveScene, InteractiveSceneCfg from isaaclab.ui.xr_widgets import DataCollector, TriggerType, VisualizationManager, XRVisualization, update_instruction from isaaclab.utils import configclass @@ -241,7 +242,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(dt=0.005) + sim_cfg = sim_utils.SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.005)) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=(8, 0, 4), target=(0.0, 0.0, 0.0)) diff --git a/source/isaaclab_contrib/test/sensors/test_visuotactile_sensor.py b/source/isaaclab_contrib/test/sensors/test_visuotactile_sensor.py index 251593b8079..a9bba23b62d 100644 --- a/source/isaaclab_contrib/test/sensors/test_visuotactile_sensor.py +++ b/source/isaaclab_contrib/test/sensors/test_visuotactile_sensor.py @@ -24,6 +24,7 @@ import isaaclab.sim as sim_utils from isaaclab.assets import Articulation, ArticulationCfg, RigidObject, RigidObjectCfg +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sensors.camera import TiledCameraCfg from isaaclab.terrains.trimesh.utils import make_plane from isaaclab.terrains.utils import create_prim_from_mesh @@ -124,7 +125,7 @@ def setup(sensor_type: str = "cube"): dt = 0.01 # Load kit helper - sim_cfg = sim_utils.SimulationCfg(dt=dt) + sim_cfg = sim_utils.SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=dt)) sim = sim_utils.SimulationContext(sim_cfg) # Ground-plane diff --git a/source/isaaclab_physx/isaaclab_physx/assets/articulation/articulation.py b/source/isaaclab_physx/isaaclab_physx/assets/articulation/articulation.py index 7bda2f011b1..2a5ded8c4c5 100644 --- a/source/isaaclab_physx/isaaclab_physx/assets/articulation/articulation.py +++ b/source/isaaclab_physx/isaaclab_physx/assets/articulation/articulation.py @@ -17,7 +17,7 @@ import warp as wp from prettytable import PrettyTable -from isaacsim.core.simulation_manager import SimulationManager +from isaaclab_physx.physics import PhysxManager as SimulationManager from pxr import PhysxSchema, UsdPhysics import isaaclab.utils.math as math_utils diff --git a/source/isaaclab_physx/isaaclab_physx/assets/articulation/articulation_data.py b/source/isaaclab_physx/isaaclab_physx/assets/articulation/articulation_data.py index adcf80a6a38..bb6f21eb0de 100644 --- a/source/isaaclab_physx/isaaclab_physx/assets/articulation/articulation_data.py +++ b/source/isaaclab_physx/isaaclab_physx/assets/articulation/articulation_data.py @@ -11,7 +11,7 @@ import torch -from isaacsim.core.simulation_manager import SimulationManager +from isaaclab_physx.physics import PhysxManager as SimulationManager from isaaclab.assets.articulation.base_articulation_data import BaseArticulationData from isaaclab.utils.buffers import TimestampedBuffer diff --git a/source/isaaclab_physx/isaaclab_physx/assets/deformable_object/deformable_object.py b/source/isaaclab_physx/isaaclab_physx/assets/deformable_object/deformable_object.py index b07c5156cad..40df6bbb85e 100644 --- a/source/isaaclab_physx/isaaclab_physx/assets/deformable_object/deformable_object.py +++ b/source/isaaclab_physx/isaaclab_physx/assets/deformable_object/deformable_object.py @@ -12,7 +12,7 @@ import torch import omni.physics.tensors.impl.api as physx -from isaacsim.core.simulation_manager import SimulationManager +from isaaclab_physx.physics import PhysxManager as SimulationManager from pxr import PhysxSchema, UsdShade import isaaclab.sim as sim_utils diff --git a/source/isaaclab_physx/isaaclab_physx/assets/rigid_object/rigid_object.py b/source/isaaclab_physx/isaaclab_physx/assets/rigid_object/rigid_object.py index 4571ab660aa..5806f8cbc89 100644 --- a/source/isaaclab_physx/isaaclab_physx/assets/rigid_object/rigid_object.py +++ b/source/isaaclab_physx/isaaclab_physx/assets/rigid_object/rigid_object.py @@ -14,7 +14,7 @@ import warp as wp import omni.physics.tensors.impl.api as physx -from isaacsim.core.simulation_manager import SimulationManager +from isaaclab_physx.physics import PhysxManager as SimulationManager from pxr import UsdPhysics import isaaclab.sim as sim_utils diff --git a/source/isaaclab_physx/isaaclab_physx/assets/rigid_object/rigid_object_data.py b/source/isaaclab_physx/isaaclab_physx/assets/rigid_object/rigid_object_data.py index a35b853cffa..7f3716b87d6 100644 --- a/source/isaaclab_physx/isaaclab_physx/assets/rigid_object/rigid_object_data.py +++ b/source/isaaclab_physx/isaaclab_physx/assets/rigid_object/rigid_object_data.py @@ -11,7 +11,7 @@ import torch -from isaacsim.core.simulation_manager import SimulationManager +from isaaclab_physx.physics import PhysxManager as SimulationManager from isaaclab.assets.rigid_object.base_rigid_object_data import BaseRigidObjectData from isaaclab.utils.buffers import TimestampedBuffer diff --git a/source/isaaclab_physx/isaaclab_physx/assets/rigid_object_collection/rigid_object_collection.py b/source/isaaclab_physx/isaaclab_physx/assets/rigid_object_collection/rigid_object_collection.py index 1e7e6caf3d4..1c7b52075be 100644 --- a/source/isaaclab_physx/isaaclab_physx/assets/rigid_object_collection/rigid_object_collection.py +++ b/source/isaaclab_physx/isaaclab_physx/assets/rigid_object_collection/rigid_object_collection.py @@ -15,7 +15,7 @@ import warp as wp import omni.physics.tensors.impl.api as physx -from isaacsim.core.simulation_manager import SimulationManager +from isaaclab_physx.physics import PhysxManager as SimulationManager from pxr import UsdPhysics import isaaclab.sim as sim_utils diff --git a/source/isaaclab_physx/isaaclab_physx/assets/rigid_object_collection/rigid_object_collection_data.py b/source/isaaclab_physx/isaaclab_physx/assets/rigid_object_collection/rigid_object_collection_data.py index 7ef9780440f..dda885b78db 100644 --- a/source/isaaclab_physx/isaaclab_physx/assets/rigid_object_collection/rigid_object_collection_data.py +++ b/source/isaaclab_physx/isaaclab_physx/assets/rigid_object_collection/rigid_object_collection_data.py @@ -11,7 +11,7 @@ import torch -from isaacsim.core.simulation_manager import SimulationManager +from isaaclab_physx.physics import PhysxManager as SimulationManager from isaaclab.assets.rigid_object_collection.base_rigid_object_collection_data import BaseRigidObjectCollectionData from isaaclab.utils.buffers import TimestampedBuffer diff --git a/source/isaaclab_physx/isaaclab_physx/physics/__init__.py b/source/isaaclab_physx/isaaclab_physx/physics/__init__.py new file mode 100644 index 00000000000..0f4c342f156 --- /dev/null +++ b/source/isaaclab_physx/isaaclab_physx/physics/__init__.py @@ -0,0 +1,16 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Implementation backends for simulation interfaces.""" + +from .physx_manager import PhysxManager, IsaacEvents +from .physx_manager_cfg import PhysxManagerCfg + + +__all__ = [ + "PhysxManager", + "IsaacEvents", + "PhysxManagerCfg", +] diff --git a/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py b/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py new file mode 100644 index 00000000000..4e566f579f0 --- /dev/null +++ b/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py @@ -0,0 +1,563 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""PhysX Manager for Isaac Lab. + +This module manages PhysX physics simulation lifecycle, configuration, callbacks, and physics views. +""" + +from __future__ import annotations + +import glob +import logging +import os +import re +import time +from datetime import datetime +from enum import Enum +from typing import TYPE_CHECKING, Any, Callable, ClassVar + +import carb +import omni.kit.app +import omni.physics.tensors +import omni.physx +import omni.timeline +import omni.usd +import torch +from pxr import PhysxSchema, Sdf + +import isaaclab.sim as sim_utils + +from isaaclab.physics import PhysicsManager, PhysicsEvent, CallbackHandle + +if TYPE_CHECKING: + from isaaclab.sim.simulation_context import SimulationContext + + from .physx_manager_cfg import PhysxManagerCfg + +__all__ = ["IsaacEvents", "PhysxManager"] + +logger = logging.getLogger(__name__) + + +class IsaacEvents(Enum): + """Events dispatched during simulation lifecycle. + + Note: This enum is kept for backward compatibility. New code should use + PhysicsEvent from physics_manager for cross-backend compatibility. + """ + + PHYSICS_WARMUP = "isaac.physics_warmup" + SIMULATION_VIEW_CREATED = "isaac.simulation_view_created" + PHYSICS_READY = "isaac.physics_ready" + POST_RESET = "isaac.post_reset" + PRIM_DELETION = "isaac.prim_deletion" + PRE_PHYSICS_STEP = "isaac.pre_physics_step" + POST_PHYSICS_STEP = "isaac.post_physics_step" + TIMELINE_STOP = "isaac.timeline_stop" + + +_PHYSICS_EVENT_TO_ISAAC_EVENT: dict[PhysicsEvent, IsaacEvents] = { + PhysicsEvent.MODEL_INIT: IsaacEvents.PHYSICS_WARMUP, + PhysicsEvent.PHYSICS_READY: IsaacEvents.PHYSICS_READY, + PhysicsEvent.PRE_STEP: IsaacEvents.PRE_PHYSICS_STEP, + PhysicsEvent.POST_STEP: IsaacEvents.POST_PHYSICS_STEP, + PhysicsEvent.STOP: IsaacEvents.TIMELINE_STOP, +} + + +class AnimationRecorder: + """Handles animation recording using PhysX PVD interface.""" + + def __init__(self, carb_settings: carb.settings.ISettings): + self._settings = carb_settings + self._enabled = bool(carb_settings.get("/isaaclab/anim_recording/enabled")) + self._started_at: float | None = None + self._physx_pvd = None + + if self._enabled: + self._start_time = carb_settings.get("/isaaclab/anim_recording/start_time") + self._stop_time = carb_settings.get("/isaaclab/anim_recording/stop_time") + self._setup_output_dir() + + def _setup_output_dir(self) -> None: + """Initialize recording directory and PVD interface.""" + from omni.physxpvd.bindings import _physxPvd + + repo_path = os.path.join(carb.tokens.get_tokens_interface().resolve("${app}"), "..") + timestamp = datetime.now().strftime("%Y_%m_%d_%H%M%S") + self._output_dir = os.path.join(repo_path, "anim_recordings", timestamp).replace("\\", "/").rstrip("/") + "/" + os.makedirs(self._output_dir, exist_ok=True) + + self._physx_pvd = _physxPvd.acquire_physx_pvd_interface() + self._settings.set_string("/persistent/physics/omniPvdOvdRecordingDirectory", self._output_dir) + self._settings.set_bool("/physics/omniPvdOutputEnabled", True) + + @property + def enabled(self) -> bool: + return self._enabled + + def update(self) -> bool: + """Update recording state. Returns True if recording finished.""" + if not self._enabled: + return False + if self._started_at is None: + self._started_at = time.time() + if time.time() - self._started_at > self._stop_time: + self._finish() + return True + return False + + def _finish(self) -> None: + """Finalize and export the recording.""" + logger.warning("[AnimationRecorder] Finishing recording. This may take a few minutes.") + + physx = omni.physx.get_physx_simulation_interface() + physx.detach_stage() + + stage_path = os.path.join(self._output_dir, "stage_simulation.usdc") + sim_utils.save_stage(stage_path, save_and_reload_in_place=False) + + ovd_files = [f for f in glob.glob(os.path.join(self._output_dir, "*.ovd")) if not f.endswith("tmp.ovd")] + if ovd_files and self._physx_pvd: + input_ovd = max(ovd_files, key=os.path.getctime) + self._physx_pvd.ovd_to_usd_over_with_layer_creation( + input_ovd, stage_path, self._output_dir, "baked_animation_recording.usda", + self._start_time, self._stop_time, True, False + ) + self._update_usda_start_time(os.path.join(self._output_dir, "baked_animation_recording.usda")) + + self._settings.set_bool("/physics/omniPvdOutputEnabled", False) + + def _update_usda_start_time(self, file_path: str) -> None: + """Patch the start time in the exported USDA file.""" + with open(file_path) as f: + content = f.read() + match = re.search(r"timeCodesPerSecond\s*=\s*(\d+)", content) + if match: + fps = int(match.group(1)) + new_start = int(self._start_time * fps) + content = re.sub(r"startTimeCode\s*=\s*\d+", f"startTimeCode = {new_start}", content) + with open(file_path, "w") as f: + f.write(content) + + +class PhysxManager(PhysicsManager): + """Manages PhysX physics simulation lifecycle. + + Lifecycle: initialize() -> reset() -> step() (repeated) -> close() + """ + + _cfg: ClassVar["PhysxManagerCfg | None"] = None + + _timeline: ClassVar[omni.timeline.ITimeline] = omni.timeline.get_timeline_interface() + _event_bus: ClassVar[carb.eventdispatcher.IEventDispatcher] = carb.eventdispatcher.get_eventdispatcher() + _physx: ClassVar[omni.physx.IPhysx] = omni.physx.get_physx_interface() + _physx_sim: ClassVar[omni.physx.IPhysxSimulation] = omni.physx.get_physx_simulation_interface() + + _view: ClassVar[omni.physics.tensors.SimulationView | None] = None + _view_warp: ClassVar[omni.physics.tensors.SimulationView | None] = None + _warmup_needed: ClassVar[bool] = True + _view_created: ClassVar[bool] = False + _assets_loaded: ClassVar[bool] = True + _stage_id: ClassVar[int] = -1 + _subscriptions: ClassVar[dict[str, Any]] = {} + _fabric: ClassVar[Any] = None + _update_fabric: ClassVar[Callable[[float, float], None] | None] = None + _anim_recorder: ClassVar[AnimationRecorder | None] = None + _callback_exception: ClassVar[Exception | None] = None + + class _SimManagerStub: + """No-op stub for Isaac Sim APIs expecting simulation_manager_interface.""" + + def reset(self) -> None: + pass + + def get_simulation_time(self) -> float: + return omni.physx.get_physx_interface().get_simulation_time() + + def is_simulating(self) -> bool: + return omni.physx.get_physx_interface().is_simulating() + + def __getattr__(self, name: str) -> Callable[..., Any]: + return lambda *a, **kw: None + + # field stubs for Isaac Sim APIs expecting simulation_manager_interface + _simulation_manager_interface: ClassVar[_SimManagerStub] = _SimManagerStub() + _physics_scene_apis: ClassVar[dict[str, Any]] = {} + _message_bus = _event_bus + + @classmethod + def initialize(cls, sim_context: "SimulationContext") -> None: + """Initialize the physics manager.""" + from isaaclab.sim.utils.stage import get_current_stage_id + + super().initialize(sim_context) + cls._stage_id = get_current_stage_id() + cls._setup_subscriptions() + cls._configure_physics() + cls._load_fabric() + cls._anim_recorder = AnimationRecorder(sim_context.carb_settings) + + # force update cycle to apply dt + sim = PhysicsManager._sim + sim.set_setting("/app/player/playSimulations", False) # type: ignore[union-attr] + omni.kit.app.get_app().update() + sim.set_setting("/app/player/playSimulations", True) # type: ignore[union-attr] + + @classmethod + def reset(cls, soft: bool = False) -> None: + """Reset the physics simulation.""" + if not soft and cls._view is None: + cls._warmup_and_create_views() + + device = PhysicsManager._device + if "cuda" in device: + torch.cuda.set_device(device) + + if cls._view is not None: + cls._view._backend.initialize_kinematic_bodies() + + cls.raise_callback_exception_if_any() + + @classmethod + def forward(cls) -> None: + """Update articulation kinematics and fabric for rendering.""" + sim = PhysicsManager._sim + if cls._fabric is not None and cls._update_fabric is not None: + if cls._view is not None and sim is not None and sim.is_playing(): + cls._view.update_articulations_kinematic() + cls._update_fabric(0.0, 0.0) + + @classmethod + def step(cls) -> None: + """Step the physics simulation.""" + cfg = PhysicsManager._cfg + if cfg is None: + return + + if cls._anim_recorder and cls._anim_recorder.enabled and cls._anim_recorder.update(): + logger.warning("Animation recording finished. Shutting down.") + omni.kit.app.get_app().shutdown() + return + + cls._physx_sim.simulate(cfg.dt, 0.0) + cls._physx_sim.fetch_results() + + device = PhysicsManager._device + if "cuda" in device: + torch.cuda.set_device(device) + + cls.raise_callback_exception_if_any() + + @classmethod + def close(cls) -> None: + """Clean up physics resources.""" + cls._event_bus.dispatch_event(IsaacEvents.PRIM_DELETION.value, payload={"prim_path": "/"}) + cls._invalidate_views() + cls._subscriptions.clear() + + if cls._physx_sim is not None: + cls._physx_sim.detach_stage() + + cls._fabric = None + cls._update_fabric = None + cls._anim_recorder = None + cls._warmup_needed = True + cls._view_created = False + cls._assets_loaded = True + cls._callback_exception = None + + super().close() + + @classmethod + def get_physics_sim_view(cls) -> omni.physics.tensors.SimulationView | None: + return cls._view + + @classmethod + def assets_loading(cls) -> bool: + return not cls._assets_loaded + + @classmethod + def store_callback_exception(cls, exception: Exception) -> None: + """Store an exception from a callback to be raised later. + + Omniverse event systems catch exceptions internally. Use this to store + exceptions that should be surfaced after the event dispatch completes. + """ + if cls._callback_exception is None: + cls._callback_exception = exception + + @classmethod + def raise_callback_exception_if_any(cls) -> None: + """Raise any stored callback exception and clear it. + + Call this after operations that may trigger callbacks (reset, step, etc.) + to propagate exceptions from Omniverse event callbacks. + """ + if cls._callback_exception is not None: + exc = cls._callback_exception + cls._callback_exception = None + raise exc + + @classmethod + def register_callback( + cls, callback: Callable, event: PhysicsEvent | IsaacEvents, order: int = 0, + name: str | None = None, wrap_weak_ref: bool = True, + ) -> CallbackHandle: + """Register a callback. Accepts both PhysicsEvent and IsaacEvents.""" + if isinstance(event, IsaacEvents): + cid = cls._callback_id + cls._callback_id += 1 + cb = cls._wrap_weak_ref(callback) if wrap_weak_ref else callback + sub = cls._subscribe_isaac(cb, event, order, name) + cls._callbacks[cid] = (event, cb, order, name, sub) + return CallbackHandle(cid, cls) + return super().register_callback(callback, event, order, name, wrap_weak_ref) + + @classmethod + def _subscribe_to_event( + cls, callback_id: int, callback: Callable, event: PhysicsEvent, order: int, name: str | None + ) -> Any: + """Subscribe to PhysX events. Maps PhysicsEvent → IsaacEvents.""" + isaac_event = _PHYSICS_EVENT_TO_ISAAC_EVENT.get(event) + return cls._subscribe_isaac(callback, isaac_event, order, name) if isaac_event else None + + @classmethod + def _subscribe_isaac(cls, callback: Callable, event: IsaacEvents, order: int, name: str | None) -> Any: + """Subscribe to an IsaacEvents event.""" + + def guarded(cb: Callable) -> Callable: + def wrapper(dt: float) -> Any: + return cb(dt) if cls._view_created else None + return wrapper + + if event in (IsaacEvents.PHYSICS_WARMUP, IsaacEvents.PHYSICS_READY, IsaacEvents.POST_RESET, + IsaacEvents.SIMULATION_VIEW_CREATED, IsaacEvents.PRIM_DELETION): + return cls._event_bus.observe_event(event_name=event.value, order=order, on_event=callback) + elif event == IsaacEvents.POST_PHYSICS_STEP: + return cls._physx.subscribe_physics_on_step_events(guarded(callback), pre_step=False, order=order) + elif event == IsaacEvents.PRE_PHYSICS_STEP: + return cls._physx.subscribe_physics_on_step_events(guarded(callback), pre_step=True, order=order) + elif event == IsaacEvents.TIMELINE_STOP: + return cls._timeline.get_timeline_event_stream().create_subscription_to_pop_by_type( + int(omni.timeline.TimelineEventType.STOP), callback, order=order, name=name + ) + return None + + @classmethod + def _setup_subscriptions(cls) -> None: + """Subscribe to timeline events.""" + if "play" in cls._subscriptions: + return + stream = cls._timeline.get_timeline_event_stream() + cls._subscriptions["play"] = stream.create_subscription_to_pop_by_type( + int(omni.timeline.TimelineEventType.PLAY), cls._on_play + ) + cls._subscriptions["stop"] = stream.create_subscription_to_pop_by_type( + int(omni.timeline.TimelineEventType.STOP), cls._on_stop + ) + if "stage_open" not in cls._subscriptions: + ctx = omni.usd.get_context() + cls._subscriptions["stage_open"] = cls._event_bus.observe_event( + event_name=ctx.stage_event_name(omni.usd.StageEventType.OPENED), on_event=cls._on_stage_open + ) + + @classmethod + def _configure_physics(cls) -> None: + """Apply all physics settings.""" + # Access base class variables since that's where initialize() sets them + sim = PhysicsManager._sim + cfg = PhysicsManager._cfg + if sim is None or cfg is None: + return + + settings = sim.carb_settings + device = sim.device + + # global carb settings + settings.set_bool("/persistent/omnihydra/useSceneGraphInstancing", True) + settings.set_bool("/physics/physxDispatcher", True) + settings.set_bool("/physics/disableContactProcessing", True) + settings.set_bool("/physics/collisionConeCustomGeometry", False) + settings.set_bool("/physics/collisionCylinderCustomGeometry", False) + settings.set_bool("/physics/autoPopupSimulationOutputWindow", False) + + # device setup (set on PhysicsManager so PhysicsManager.get_device() works) + is_gpu = "cuda" in device + if is_gpu: + parts = device.split(":") + device_id = int(parts[1]) if len(parts) > 1 else max(0, settings.get_as_int("/physics/cudaDevice")) + settings.set_int("/physics/cudaDevice", device_id) + settings.set_bool("/physics/suppressReadback", True) + PhysicsManager._device = f"cuda:{device_id}" + else: + settings.set_int("/physics/cudaDevice", -1) + settings.set_bool("/physics/suppressReadback", False) + PhysicsManager._device = "cpu" + + # physx scene api + stage = sim.stage + scene_prim = stage.GetPrimAtPath(cfg.physics_prim_path) + PhysxSchema.PhysxSceneAPI.Apply(scene_prim) + scene_api = PhysxSchema.PhysxSceneAPI(scene_prim) + + # timestep and frame rate + steps_per_sec = int(1.0 / cfg.dt) + scene_api.CreateTimeStepsPerSecondAttr(steps_per_sec) + render_interval = max(sim.cfg.render_interval, 1) + settings.set_int("/persistent/simulation/minFrameRate", steps_per_sec // render_interval) + + # gpu dynamics + scene_api.CreateBroadphaseTypeAttr("GPU" if is_gpu else "MBP") + scene_api.CreateEnableGPUDynamicsAttr(is_gpu) + + # ccd (not supported on gpu) + enable_ccd = cfg.enable_ccd and not is_gpu + if cfg.enable_ccd and is_gpu: + logger.warning("CCD disabled when GPU dynamics is enabled.") + scene_api.CreateEnableCCDAttr(enable_ccd) + + # solver + scene_api.CreateSolverTypeAttr("TGS" if cfg.solver_type == 1 else "PGS") + scene_prim.CreateAttribute("physxScene:solveArticulationContactLast", Sdf.ValueTypeNames.Bool).Set( + cfg.solve_articulation_contact_last + ) + + # apply remaining cfg attributes to scene + skip = {"solver_type", "enable_ccd", "solve_articulation_contact_last", "dt", "device", + "render_interval", "gravity", "physics_prim_path", "use_fabric", "physics_material", "class_type"} + for key, value in cfg.to_dict().items(): # type: ignore + if key not in skip: + attr_name = "bounce_threshold" if key == "bounce_threshold_velocity" else key + sim_utils.safe_set_attribute_on_usd_schema(scene_api, attr_name, value, camel_case=True) + + # default physics material + if cfg.physics_material: + mat_path = f"{cfg.physics_prim_path}/defaultMaterial" + cfg.physics_material.func(mat_path, cfg.physics_material) + sim_utils.bind_physics_material(cfg.physics_prim_path, mat_path) + + # warnings + if cfg.solver_type == 1 and not cfg.enable_external_forces_every_iteration: + logger.warning("TGS solver with enable_external_forces_every_iteration=False may cause noisy velocities.") + if not cfg.enable_stabilization and cfg.dt > 0.0333: + logger.warning("Large timestep without stabilization may cause physics issues.") + + @classmethod + def _load_fabric(cls) -> None: + """Load fabric interface if enabled.""" + sim = PhysicsManager._sim + cfg = PhysicsManager._cfg + if sim is None or cfg is None: + return + + settings = sim.carb_settings + use_fabric = cfg.use_fabric + ext_mgr = omni.kit.app.get_app().get_extension_manager() + + # enable/disable fabric extension + if use_fabric: + if not ext_mgr.is_extension_enabled("omni.physx.fabric"): + ext_mgr.set_extension_enabled_immediate("omni.physx.fabric", True) + from omni.physxfabric import get_physx_fabric_interface + cls._fabric = get_physx_fabric_interface() + cls._update_fabric = getattr(cls._fabric, "force_update", cls._fabric.update) + else: + if ext_mgr.is_extension_enabled("omni.physx.fabric"): + ext_mgr.set_extension_enabled_immediate("omni.physx.fabric", False) + cls._fabric = None + cls._update_fabric = None + + # disable usd sync when fabric is enabled + for key in ["updateToUsd", "updateParticlesToUsd", "updateVelocitiesToUsd", + "updateForceSensorsToUsd", "updateResidualsToUsd"]: + settings.set_bool(f"/physics/{key}", not use_fabric) + settings.set_bool("/isaaclab/fabric_enabled", use_fabric) + settings.set_bool("/physics/visualizationDisplaySimulationOutput", False) + + @classmethod + def _warmup_and_create_views(cls) -> None: + """Warm-start physics and create simulation views.""" + if not cls._warmup_needed: + return + + # warmup physx + cls._physx.force_load_physics_from_usd() + cls._physx.start_simulation() + cls._physx.update_simulation(cls.get_physics_dt(), 0.0) + cls._physx_sim.fetch_results() + cls._event_bus.dispatch_event(IsaacEvents.PHYSICS_WARMUP.value, payload={}) + cls._warmup_needed = False + + if cls._view_created: + return + + # create tensor views + from isaaclab.sim.utils.stage import get_current_stage_id + stage_id = get_current_stage_id() + + # attach stage to PhysX before creating views + cls._physx_sim.attach_stage(stage_id) + + cls._view = omni.physics.tensors.create_simulation_view("torch", stage_id=stage_id) + cls._view_warp = omni.physics.tensors.create_simulation_view("warp", stage_id=stage_id) + + if cls._view: + cls._view.set_subspace_roots("/") + if cls._view_warp: + cls._view_warp.set_subspace_roots("/") + + cls._physx.update_simulation(cls.get_physics_dt(), 0.0) + cls._view_created = True + + cls._event_bus.dispatch_event(IsaacEvents.SIMULATION_VIEW_CREATED.value, payload={}) + cls._event_bus.dispatch_event(IsaacEvents.PHYSICS_READY.value, payload={}) + + @classmethod + def _invalidate_views(cls) -> None: + """Invalidate and clear simulation views.""" + for view in (cls._view, cls._view_warp): + if view: + view.invalidate() + cls._view = None + cls._view_warp = None + cls._view_created = False + + @classmethod + def _on_play(cls, event: Any) -> None: + if carb.settings.get_settings().get_as_bool("/app/player/playSimulations"): + cls._warmup_and_create_views() + + @classmethod + def _on_stop(cls, event: Any) -> None: + cls._warmup_needed = True + cls._invalidate_views() + + @classmethod + def _on_stage_open(cls, event: Any) -> None: + from isaaclab.sim.utils.stage import get_current_stage_id + + new_stage_id = get_current_stage_id() + if new_stage_id == cls._stage_id: + return + + cls._stage_id = new_stage_id + cls._callbacks.clear() + cls._assets_loaded = True + + def on_loading(e: Any) -> None: + cls._assets_loaded = False + + def on_loaded(e: Any) -> None: + cls._assets_loaded = True + + ctx = omni.usd.get_context() + cls._subscriptions["assets_loading"] = cls._event_bus.observe_event( + event_name=ctx.stage_event_name(omni.usd.StageEventType.ASSETS_LOADING), on_event=on_loading + ) + cls._subscriptions["assets_loaded"] = cls._event_bus.observe_event( + event_name=ctx.stage_event_name(omni.usd.StageEventType.ASSETS_LOADED), on_event=on_loaded + ) diff --git a/source/isaaclab_physx/isaaclab_physx/physics/physx_manager_cfg.py b/source/isaaclab_physx/isaaclab_physx/physics/physx_manager_cfg.py new file mode 100644 index 00000000000..936c83bd9ce --- /dev/null +++ b/source/isaaclab_physx/isaaclab_physx/physics/physx_manager_cfg.py @@ -0,0 +1,225 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Configuration for PhysX physics manager.""" + +from __future__ import annotations + +from typing import TYPE_CHECKING, Literal + +from isaaclab.utils import configclass +from isaaclab.physics import PhysicsManagerCfg + +from .physx_manager import PhysxManager + +if TYPE_CHECKING: + from isaaclab.physics import PhysicsManager + + +@configclass +class PhysxManagerCfg(PhysicsManagerCfg): + """Configuration for PhysX physics manager. + + This configuration includes all PhysX-specific settings including solver + parameters, scene configuration, and GPU buffer sizes. For more information, + see the `PhysX 5 SDK documentation`_. + + PhysX 5 supports GPU-accelerated physics simulation. This is enabled by default, + but can be disabled by setting :attr:`device` to ``cpu``. Unlike CPU PhysX, the + GPU simulation feature is unable to dynamically grow all the buffers. Therefore, + it is necessary to provide a reasonable estimate of the buffer sizes for GPU + features. If insufficient buffer sizes are provided, the simulation will fail + with errors and lead to adverse behaviors. The buffer sizes can be adjusted + through the ``gpu_*`` parameters. + + .. _PhysX 5 SDK documentation: https://nvidia-omniverse.github.io/PhysX/physx/5.4.1/_api_build/classPxSceneDesc.html + """ + + # ------------------------------------------------------------------ + # PhysX Scene Settings + # ------------------------------------------------------------------ + + class_type: type[PhysicsManager] = PhysxManager + """The class type of the PhysxManager.""" + + physics_prim_path: str = "/physicsScene" + """The prim path where the USD PhysicsScene is created. Default is "/physicsScene".""" + + use_fabric: bool = True + """Enable/disable reading of physics buffers directly. Default is True. + + When running the simulation, updates in the states in the scene is normally synchronized with USD. + This leads to an overhead in reading the data and does not scale well with massive parallelization. + This flag allows disabling the synchronization and reading the data directly from the physics buffers. + + It is recommended to set this flag to :obj:`True` when running the simulation with a large number + of primitives in the scene. + """ + + # ------------------------------------------------------------------ + # Solver Settings + # ------------------------------------------------------------------ + + solver_type: Literal[0, 1] = 1 + """The type of solver to use. Default is 1 (TGS). + + Available solvers: + + * :obj:`0`: PGS (Projective Gauss-Seidel) + * :obj:`1`: TGS (Temporal Gauss-Seidel) + """ + + solve_articulation_contact_last: bool = False + """Changes the ordering inside the articulation solver. Default is False. + + PhysX employs a strict ordering for handling constraints in an articulation. The outcome of + each constraint resolution modifies the joint and associated link speeds. However, the default + ordering may not be ideal for gripping scenarios because the solver favours the constraint + types that are resolved last. This is particularly true of stiff constraint systems that are hard + to resolve without resorting to vanishingly small simulation timesteps. + + With dynamic contact resolution being such an important part of gripping, it may make + more sense to solve dynamic contact towards the end of the solver rather than at the + beginning. This parameter modifies the default ordering to enable this change. + + For more information, please check `here `__. + + .. versionadded:: v2.3 + This parameter is only available with Isaac Sim 5.1. + """ + + min_position_iteration_count: int = 1 + """Minimum number of solver position iterations (rigid bodies, cloth, particles etc.). Default is 1. + + .. note:: + + Each physics actor in Omniverse specifies its own solver iteration count. The solver takes + the number of iterations specified by the actor with the highest iteration and clamps it to + the range ``[min_position_iteration_count, max_position_iteration_count]``. + """ + + max_position_iteration_count: int = 255 + """Maximum number of solver position iterations (rigid bodies, cloth, particles etc.). Default is 255. + + .. note:: + + Each physics actor in Omniverse specifies its own solver iteration count. The solver takes + the number of iterations specified by the actor with the highest iteration and clamps it to + the range ``[min_position_iteration_count, max_position_iteration_count]``. + """ + + min_velocity_iteration_count: int = 0 + """Minimum number of solver velocity iterations (rigid bodies, cloth, particles etc.). Default is 0. + + .. note:: + + Each physics actor in Omniverse specifies its own solver iteration count. The solver takes + the number of iterations specified by the actor with the highest iteration and clamps it to + the range ``[min_velocity_iteration_count, max_velocity_iteration_count]``. + """ + + max_velocity_iteration_count: int = 255 + """Maximum number of solver velocity iterations (rigid bodies, cloth, particles etc.). Default is 255. + + .. note:: + + Each physics actor in Omniverse specifies its own solver iteration count. The solver takes + the number of iterations specified by the actor with the highest iteration and clamps it to + the range ``[min_velocity_iteration_count, max_velocity_iteration_count]``. + """ + + enable_ccd: bool = False + """Enable a second broad-phase pass that makes it possible to prevent objects from tunneling through each other. + Default is False.""" + + enable_stabilization: bool = False + """Enable/disable additional stabilization pass in solver. Default is False. + + .. note:: + + We recommend setting this flag to true only when the simulation step size is large (i.e., less than 30 Hz or more than 0.0333 seconds). + + .. warning:: + + Enabling this flag may lead to incorrect contact forces report from the contact sensor. + """ + + enable_external_forces_every_iteration: bool = False + """Enable/disable external forces every position iteration in the TGS solver. Default is False. + + When using the TGS solver (:attr:`solver_type` is 1), this flag allows enabling external forces every solver position iteration. + This can help improve the accuracy of velocity updates. Consider enabling this flag if the velocities generated by + the simulation are noisy. Increasing the number of velocity iterations, together with this flag, can help improve + the accuracy of velocity updates. + + .. note:: + + This flag is ignored when using the PGS solver (:attr:`solver_type` is 0). + """ + + enable_enhanced_determinism: bool = False + """Enable/disable improved determinism at the expense of performance. Defaults to False. + + For more information on PhysX determinism, please check `here`_. + + .. _here: https://nvidia-omniverse.github.io/PhysX/physx/5.4.1/docs/RigidBodyDynamics.html#enhanced-determinism + """ + + bounce_threshold_velocity: float = 0.5 + """Relative velocity threshold for contacts to bounce (in m/s). Default is 0.5 m/s.""" + + friction_offset_threshold: float = 0.04 + """Threshold for contact point to experience friction force (in m). Default is 0.04 m.""" + + friction_correlation_distance: float = 0.025 + """Distance threshold for merging contacts into a single friction anchor point (in m). Default is 0.025 m.""" + + # ------------------------------------------------------------------ + # GPU Buffer Settings + # ------------------------------------------------------------------ + + gpu_max_rigid_contact_count: int = 2**23 + """Size of rigid contact stream buffer allocated in pinned host memory. Default is 2 ** 23.""" + + gpu_max_rigid_patch_count: int = 5 * 2**15 + """Size of the rigid contact patch stream buffer allocated in pinned host memory. Default is 5 * 2 ** 15.""" + + gpu_found_lost_pairs_capacity: int = 2**21 + """Capacity of found and lost buffers allocated in GPU global memory. Default is 2 ** 21. + + This is used for the found/lost pair reports in the BP. + """ + + gpu_found_lost_aggregate_pairs_capacity: int = 2**25 + """Capacity of found and lost buffers in aggregate system allocated in GPU global memory. + Default is 2 ** 25. + + This is used for the found/lost pair reports in AABB manager. + """ + + gpu_total_aggregate_pairs_capacity: int = 2**21 + """Capacity of total number of aggregate pairs allocated in GPU global memory. Default is 2 ** 21.""" + + gpu_collision_stack_size: int = 2**26 + """Size of the collision stack buffer allocated in pinned host memory. Default is 2 ** 26.""" + + gpu_heap_capacity: int = 2**26 + """Initial capacity of the GPU and pinned host memory heaps. Additional memory will be allocated + if more memory is required. Default is 2 ** 26.""" + + gpu_temp_buffer_capacity: int = 2**24 + """Capacity of temp buffer allocated in pinned host memory. Default is 2 ** 24.""" + + gpu_max_num_partitions: int = 8 + """Limitation for the partitions in the GPU dynamics pipeline. Default is 8. + + This variable must be power of 2. A value greater than 32 is currently not supported. Range: (1, 32) + """ + + gpu_max_soft_body_contacts: int = 2**20 + """Size of soft body contacts stream buffer allocated in pinned host memory. Default is 2 ** 20.""" + + gpu_max_particle_contacts: int = 2**20 + """Size of particle contacts stream buffer allocated in pinned host memory. Default is 2 ** 20.""" diff --git a/source/isaaclab_physx/isaaclab_physx/sensors/contact_sensor/contact_sensor.py b/source/isaaclab_physx/isaaclab_physx/sensors/contact_sensor/contact_sensor.py index 815d931f8cd..c1c37a9f1d4 100644 --- a/source/isaaclab_physx/isaaclab_physx/sensors/contact_sensor/contact_sensor.py +++ b/source/isaaclab_physx/isaaclab_physx/sensors/contact_sensor/contact_sensor.py @@ -15,7 +15,7 @@ import carb import omni.physics.tensors.impl.api as physx -from isaacsim.core.simulation_manager import SimulationManager +from isaaclab_physx.physics import PhysxManager as SimulationManager from pxr import PhysxSchema import isaaclab.sim as sim_utils diff --git a/source/isaaclab_physx/isaaclab_physx/sensors/frame_transformer/frame_transformer.py b/source/isaaclab_physx/isaaclab_physx/sensors/frame_transformer/frame_transformer.py index 28d45b67f91..63f77950c8b 100644 --- a/source/isaaclab_physx/isaaclab_physx/sensors/frame_transformer/frame_transformer.py +++ b/source/isaaclab_physx/isaaclab_physx/sensors/frame_transformer/frame_transformer.py @@ -12,7 +12,7 @@ import torch -from isaacsim.core.simulation_manager import SimulationManager +from isaaclab_physx.physics import PhysxManager as SimulationManager from pxr import UsdPhysics import isaaclab.sim as sim_utils diff --git a/source/isaaclab_physx/isaaclab_physx/sensors/imu/imu.py b/source/isaaclab_physx/isaaclab_physx/sensors/imu/imu.py index 1d6e2e96753..89593b4f012 100644 --- a/source/isaaclab_physx/isaaclab_physx/sensors/imu/imu.py +++ b/source/isaaclab_physx/isaaclab_physx/sensors/imu/imu.py @@ -10,7 +10,7 @@ import torch -from isaacsim.core.simulation_manager import SimulationManager +from isaaclab_physx.physics import PhysxManager as SimulationManager from pxr import UsdGeom, UsdPhysics import isaaclab.sim as sim_utils diff --git a/source/isaaclab_physx/isaaclab_physx/visualizers/__init__.py b/source/isaaclab_physx/isaaclab_physx/visualizers/__init__.py new file mode 100644 index 00000000000..024a54ab45a --- /dev/null +++ b/source/isaaclab_physx/isaaclab_physx/visualizers/__init__.py @@ -0,0 +1,51 @@ +# # Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# # All rights reserved. +# # +# # SPDX-License-Identifier: BSD-3-Clause + +# """Sub-package for visualizer configurations and implementations. + +from __future__ import annotations + +from typing import TYPE_CHECKING + +# Import config classes (no circular dependency) +from .physx_ov_visualizer_cfg import PhysxOVVisualizerCfg + +from isaaclab.visualizers import _VISUALIZER_REGISTRY + +if TYPE_CHECKING: + from isaaclab.visualizers import Visualizer + +__all__ = [ + "PhysxOVVisualizerCfg", +] + + +# # Register only selected visualizers to reduce unnecessary imports +def get_visualizer_class(name: str) -> type[Visualizer] | None: + """Get a visualizer class by name (lazy-loaded). + + Visualizer classes are imported only when requested to avoid loading + unnecessary dependencies. + + Args: + name: Visualizer type name (e.g., 'newton', 'rerun', 'omniverse'). + + Returns: + Visualizer class if found, None otherwise. + + Example: + >>> visualizer_cls = get_visualizer_class('newton') + >>> if visualizer_cls: + >>> visualizer = visualizer_cls(cfg) + """ + # Check if already loaded + if name in _VISUALIZER_REGISTRY: + return _VISUALIZER_REGISTRY[name] + + if name == "isaacsim_ov": + from .physx_ov_visualizer_cfg import PhysxOVVisualizerCfg + + _VISUALIZER_REGISTRY["isaacsim_ov"] = PhysxOVVisualizerCfg + return PhysxOVVisualizerCfg diff --git a/source/isaaclab_physx/isaaclab_physx/visualizers/physx_ov_visualizer.py b/source/isaaclab_physx/isaaclab_physx/visualizers/physx_ov_visualizer.py new file mode 100644 index 00000000000..2d62b4d17b6 --- /dev/null +++ b/source/isaaclab_physx/isaaclab_physx/visualizers/physx_ov_visualizer.py @@ -0,0 +1,759 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Omniverse visualizer for PhysX-based SimulationContext.""" + +from __future__ import annotations + +import enum +import flatdict +import logging +import os +import toml +import torch +import weakref +from typing import TYPE_CHECKING, Any, Callable + +import omni.kit.app +import omni.timeline +from isaaclab.utils.version import get_isaac_sim_version +from isaaclab.visualizers import Visualizer + +if TYPE_CHECKING: + import carb + + from .physx_ov_visualizer_cfg import PhysxOVVisualizerCfg + from isaaclab.sim.simulation_context import SimulationContext + +logger = logging.getLogger(__name__) + + +class RenderMode(enum.IntEnum): + """Different rendering modes for the simulation. + + Render modes correspond to how the viewport and other UI elements (such as listeners to keyboard or mouse + events) are updated. There are three main components that can be updated when the simulation is rendered: + + 1. **UI elements and other extensions**: These are UI elements (such as buttons, sliders, etc.) and other + extensions that are running in the background that need to be updated when the simulation is running. + 2. **Cameras**: These are typically based on Hydra textures and are used to render the scene from different + viewpoints. They can be attached to a viewport or be used independently to render the scene. + 3. **Viewports**: These are windows where you can see the rendered scene. + + Updating each of the above components has a different overhead. For example, updating the viewports is + computationally expensive compared to updating the UI elements. Therefore, it is useful to be able to + control what is updated when the simulation is rendered. This is where the render mode comes in. There are + four different render modes: + + * :attr:`NO_GUI_OR_RENDERING`: The simulation is running without a GUI and off-screen rendering flag is disabled, + so none of the above are updated. + * :attr:`NO_RENDERING`: No rendering, where only 1 is updated at a lower rate. + * :attr:`PARTIAL_RENDERING`: Partial rendering, where only 1 and 2 are updated. + * :attr:`FULL_RENDERING`: Full rendering, where everything (1, 2, 3) is updated. + + .. _Viewports: https://docs.omniverse.nvidia.com/extensions/latest/ext_viewport.html + """ + + NO_GUI_OR_RENDERING = -1 + """The simulation is running without a GUI and off-screen rendering is disabled.""" + NO_RENDERING = 0 + """No rendering, where only other UI elements are updated at a lower rate.""" + PARTIAL_RENDERING = 1 + """Partial rendering, where the simulation cameras and UI elements are updated.""" + FULL_RENDERING = 2 + """Full rendering, where all the simulation viewports, cameras and UI elements are updated.""" + + +class TimelineControl: + """Helper class for managing timeline lifecycle (play/pause/stop). + + This class wraps the omni.timeline interface and provides a clean API + for controlling simulation playback. It can be composed by visualizers + or simulation contexts that need timeline control. + + Features: + - Play/pause/stop control with proper physics handle propagation + - Stop event callback subscription + - Timeline state queries (is_playing, is_stopped) + """ + + def __init__( + self, + app_interface: omni.kit.app.IApp, + carb_settings: "carb.settings.ISettings", + on_stop_callback: Callable[[], None] | None = None, + ): + """Initialize timeline control. + + Args: + app_interface: Omniverse Kit application interface. + carb_settings: Carb settings interface for controlling playSimulations. + on_stop_callback: Optional callback to invoke when simulation stops. + """ + self._app_iface = app_interface + self._carb_settings = carb_settings + self._on_stop_callback = on_stop_callback + + # Acquire timeline interface + self._timeline_iface = omni.timeline.get_timeline_interface() + self._timeline_iface.set_auto_update(True) + + # Setup stop handle callback + self._disable_stop_handle = False + timeline_event_stream = self._timeline_iface.get_timeline_event_stream() + self._stop_handle = timeline_event_stream.create_subscription_to_pop_by_type( + int(omni.timeline.TimelineEventType.STOP), + lambda *args, obj=weakref.proxy(self): obj._on_stop_event(*args), + order=15, + ) + + @property + def timeline_interface(self) -> omni.timeline.ITimeline: + """Get the underlying timeline interface.""" + return self._timeline_iface + + def is_playing(self) -> bool: + """Check whether the simulation is playing. + + Returns: + True if simulation is currently playing, False otherwise. + """ + return self._timeline_iface.is_playing() + + def is_stopped(self) -> bool: + """Check whether the simulation is stopped. + + Returns: + True if simulation is stopped, False otherwise. + """ + return self._timeline_iface.is_stopped() + + def play(self) -> None: + """Start playing the simulation. + + This commits the timeline state and performs one app update step + to propagate all physics handles properly. + """ + self._timeline_iface.play() + self._timeline_iface.commit() + # Perform one step to propagate all physics handles properly + self._carb_settings.set_bool("/app/player/playSimulations", False) + self._app_iface.update() + self._carb_settings.set_bool("/app/player/playSimulations", True) + + def pause(self) -> None: + """Pause the simulation. + + This commits the timeline state to ensure the pause takes effect. + """ + self._timeline_iface.pause() + self._timeline_iface.commit() + + def stop(self) -> None: + """Stop the simulation. + + This commits the timeline state and performs one app update step + to propagate all physics handles properly. + """ + self._timeline_iface.stop() + self._timeline_iface.commit() + # Perform one step to propagate all physics handles properly + self._carb_settings.set_bool("/app/player/playSimulations", False) + self._app_iface.update() + self._carb_settings.set_bool("/app/player/playSimulations", True) + + def set_stop_handle_enabled(self, enabled: bool) -> None: + """Enable or disable the stop handle callback. + + When disabled, the on_stop_callback will not be invoked when + the simulation stops. + + Args: + enabled: If True, the stop handle callback is active. + """ + self._disable_stop_handle = not enabled + + def set_target_framerate(self, hz: int) -> None: + """Set the target framerate for the timeline. + + Args: + hz: Target framerate in Hz. + """ + self._timeline_iface.set_target_framerate(hz) + + def set_time_codes_per_second(self, time_codes_per_second: float) -> None: + """Set the time codes per second for the timeline. + + Args: + time_codes_per_second: Number of time codes per second. + """ + self._timeline_iface.set_time_codes_per_second(time_codes_per_second) + + def close(self) -> None: + """Clean up timeline resources. + + Unsubscribes from the stop event and releases the timeline handle. + """ + if self._stop_handle is not None: + self._stop_handle.unsubscribe() + self._stop_handle = None + + def _on_stop_event(self, _) -> None: + """Internal callback when simulation stops. + + Invokes the on_stop_callback if the stop handle is enabled. + """ + if not self._disable_stop_handle and self._on_stop_callback is not None: + self._on_stop_callback() + + +class PhysxOVVisualizer(Visualizer): + """Omniverse visualizer managing viewport/rendering for PhysX workflow. + + This class extends the base :class:`Visualizer` and handles: + - Viewport context and window management + - Render mode switching + - Camera view setup + - Render settings from configuration + - Throttled rendering for UI responsiveness + - Timeline control (play/pause/stop) + + Lifecycle: __init__(cfg) -> initialize(scene_data) -> step() (repeated) -> close() + """ + + def __init__(self, cfg: "PhysxOVVisualizerCfg"): + """Initialize PhysX OV visualizer with configuration. + + Args: + cfg: Configuration for the visualizer. + """ + super().__init__(cfg) + self.cfg: "PhysxOVVisualizerCfg" = cfg + + # Will be set during initialize() + self._sim: "SimulationContext | None" = None + self._app_iface = None + self._timeline: TimelineControl | None = None + + # Render state + self._local_gui = False + self._livestream_gui = False + self._xr_gui = False + self._offscreen_render = False + self._render_viewport = False + + # Viewport state + self._viewport_context = None + self._viewport_window = None + self._render_throttle_counter = 0 + self._render_throttle_period = cfg.render_throttle_period + + # Render mode + self.render_mode = RenderMode.NO_GUI_OR_RENDERING + + def initialize(self, scene_data: dict[str, Any] | None = None) -> None: + """Initialize visualizer with simulation context. + + Args: + scene_data: Dictionary containing: + - 'simulation_context': The SimulationContext instance (required) + - 'usd_stage': The USD stage (optional, can get from sim context) + """ + if self._is_initialized: + logger.warning("[PhysxOVVisualizer] Already initialized.") + return + + if scene_data is None: + raise ValueError("PhysxOVVisualizer requires scene_data with 'simulation_context'") + + self._sim = scene_data.get("simulation_context") + if self._sim is None: + raise ValueError("PhysxOVVisualizer requires 'simulation_context' in scene_data") + + # Acquire application interface + self._app_iface = omni.kit.app.get_app_interface() + + # Detect render flags + self._local_gui = self._sim.carb_settings.get("/app/window/enabled") + self._livestream_gui = self._sim.carb_settings.get("/app/livestream/enabled") + self._xr_gui = self._sim.carb_settings.get("/app/xr/enabled") + self._offscreen_render = bool(self._sim.carb_settings.get("/isaaclab/render/offscreen")) + self._render_viewport = bool(self._sim.carb_settings.get("/isaaclab/render/active_viewport")) + + # Flag for whether any GUI will be rendered (local, livestreamed or viewport) + has_gui = bool(self._local_gui or self._livestream_gui or self._xr_gui) + self._sim.set_setting("/isaaclab/has_gui", has_gui) + + # Apply render settings from config + self._apply_render_settings_from_cfg() + + # Store the default render mode + if self.cfg.default_render_mode is not None: + self.render_mode = self.cfg.default_render_mode + elif not has_gui and not self._offscreen_render: + # set default render mode + # note: this is the terminal state: cannot exit from this render mode + self.render_mode = RenderMode.NO_GUI_OR_RENDERING + elif not has_gui and self._offscreen_render: + # set default render mode + # note: this is the terminal state: cannot exit from this render mode + self.render_mode = RenderMode.PARTIAL_RENDERING + 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 = RenderMode.FULL_RENDERING + # acquire viewport context + self._viewport_context = get_active_viewport() + self._viewport_context.updates_enabled = True # pyright: ignore [reportOptionalMemberAccess] + # acquire viewport window + self._viewport_window = ui.Workspace.get_window(self.cfg.viewport_name or "Viewport") + + # 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 + + # Override enable scene querying if rendering is enabled + # this is needed for some GUI features + if self._sim.carb_settings.get("/isaaclab/has_gui"): + self._sim.cfg.enable_scene_query_support = True + + # Initialize timeline control (manages play/pause/stop and stop callbacks) + self._timeline = TimelineControl( + app_interface=self._app_iface, + carb_settings=self._sim.carb_settings, + on_stop_callback=self._on_timeline_stop, + ) + + # Configure rendering/timeline rate + self._configure_rendering_dt() + + # Set initial camera view + self.set_camera_view(self.cfg.camera_position, self.cfg.camera_target) + + self._is_initialized = True + logger.info("[PhysxOVVisualizer] Initialized") + + def step(self, dt: float, state: Any | None = None) -> None: + """Update visualization for one step (render the scene). + + Args: + dt: Time step in seconds. + state: Updated physics state (unused for OV - USD stage is auto-synced). + """ + if not self._is_initialized: + return + + self.render() + + def render(self, mode: RenderMode | None = None) -> None: + """Refreshes the rendering components including UI elements and view-ports depending on the render mode. + + This function is used to refresh the rendering components of the simulation. This includes updating the + view-ports, UI elements, and other extensions (besides physics simulation) that are running in the + background. The rendering components are refreshed based on the render mode. + + Please see :class:`RenderMode` for more information on the different render modes. + + Args: + mode: The rendering mode. Defaults to None, in which case the current rendering mode is used. + """ + if self._sim is None or self._app_iface is None: + return + + # check if we need to change the render mode + if mode is not None: + self.set_render_mode(mode) + # note: we don't call super().render() anymore because they do above operation inside + # and we don't want to do it twice. We may remove it once we drop support for Isaac Sim 2022.2. + self._sim.set_setting("/app/player/playSimulations", False) + self._app_iface.update() + self._sim.set_setting("/app/player/playSimulations", True) + + # app.update() may be changing the cuda device, so we force it back to our desired device here + if "cuda" in self._sim.device: + torch.cuda.set_device(self._sim.device) + + @property + def has_gui(self) -> bool: + """Whether any GUI is available (local, livestreamed, or XR).""" + if self._sim is None: + return False + return bool(self._sim.carb_settings.get("/isaaclab/has_gui")) + + @property + def app(self) -> omni.kit.app.IApp: + """Omniverse Kit Application interface.""" + return self._app_iface + + @property + def offscreen_render(self) -> bool: + """Whether offscreen rendering is enabled.""" + return self._offscreen_render + + @property + def render_viewport(self) -> bool: + """Whether the default viewport should be rendered.""" + return self._render_viewport + + # ------------------------------------------------------------------ + # Timeline Control + # ------------------------------------------------------------------ + + @property + def timeline(self) -> TimelineControl | None: + """Get the timeline control instance.""" + return self._timeline + + def is_playing(self) -> bool: + """Check whether the simulation is playing.""" + if self._timeline is None: + return False + return self._timeline.is_playing() + + def is_stopped(self) -> bool: + """Check whether the visualizer is stopped (closed).""" + return self._is_closed + + def play(self) -> None: + """Start playing the simulation.""" + if self._timeline is not None: + self._timeline.play() + + def pause(self) -> None: + """Pause the simulation.""" + if self._timeline is not None: + self._timeline.pause() + + def stop(self) -> None: + """Stop the simulation.""" + if self._timeline is not None: + self._timeline.stop() + + # ------------------------------------------------------------------ + # Visualizer Interface Implementation + # ------------------------------------------------------------------ + + def is_running(self) -> bool: + """Check if visualizer is still running (independent of pause state).""" + return self._is_initialized and not self._is_closed + + def supports_markers(self) -> bool: + """Supports markers via USD prims.""" + return True + + def supports_live_plots(self) -> bool: + """Supports live plots via Isaac Lab UI.""" + return True + + def get_rendering_dt(self) -> float | None: + """Get rendering dt based on OV rate limiting settings.""" + if self._sim is None: + return None + + settings = self._sim.carb_settings + + def _from_frequency(): + freq = settings.get("/app/runLoops/main/rateLimitFrequency") + return 1.0 / freq if freq else None + + if settings.get("/app/runLoops/main/rateLimitEnabled"): + return _from_frequency() + + try: + import omni.kit.loop._loop as omni_loop + + runner = omni_loop.acquire_loop_interface() + return runner.get_manual_step_size() if runner.get_manual_mode() else _from_frequency() + except Exception: + return _from_frequency() + + def set_camera_view( + self, eye: tuple[float, float, float] | list[float], target: tuple[float, float, float] | list[float] + ) -> None: + """Set the location and target of the viewport camera in the stage. + + Note: + This is a wrapper around the :math:`isaacsim.core.utils.viewports.set_camera_view` function. + It is provided here for convenience to reduce the amount of imports needed. + + Args: + eye: The location of the camera eye. + target: The location of the camera target. + camera_prim_path: The path to the camera primitive in the stage. Defaults to + the value from config or "/OmniverseKit_Persp". + """ + if not self._is_initialized: + logger.warning("[PhysxOVVisualizer] Cannot set camera view - visualizer not initialized.") + return + + try: + # Import Isaac Sim viewport utilities + import isaacsim.core.utils.viewports as vp_utils + + # Get the camera prim path - use viewport context or config default + camera_path = self.cfg.camera_prim_path + + # Use Isaac Sim utility to set camera view + vp_utils.set_camera_view( + eye=list(eye), target=list(target), camera_prim_path=camera_path + ) + + logger.info(f"[PhysxOVVisualizer] Camera set: pos={eye}, target={target}, camera={camera_path}") + + except Exception as e: + logger.warning(f"[PhysxOVVisualizer] Could not set camera: {e}") + + def set_render_mode(self, mode: RenderMode) -> None: + """Change the current render mode of the simulation. + + Please see :class:`RenderMode` for more information on the different render modes. + + .. note:: + When no GUI is available (locally or livestreamed), we do not need to choose whether the viewport + needs to render or not (since there is no GUI). Thus, in this case, calling the function will not + change the render mode. + + Args: + mode: The rendering mode. If different than current rendering mode, + the mode is changed to the new mode. + + Raises: + ValueError: If the input mode is not supported. + """ + if self._sim is None: + return + + # check if mode change is possible -- not possible when no GUI is available + if not self._sim.carb_settings.get("/isaaclab/has_gui"): + logger.warning( + f"Cannot change render mode when GUI is disabled. Using the default render mode: {self.render_mode}." + ) + return + # check if there is a mode change + # note: this is mostly needed for GUI when we want to switch between full rendering and no rendering. + if mode != self.render_mode: + if mode == RenderMode.FULL_RENDERING: + # display the viewport and enable updates + self._viewport_context.updates_enabled = True # pyright: ignore [reportOptionalMemberAccess] + self._viewport_window.visible = True # pyright: ignore [reportOptionalMemberAccess] + elif mode == RenderMode.PARTIAL_RENDERING: + # hide the viewport and disable updates + self._viewport_context.updates_enabled = False # pyright: ignore [reportOptionalMemberAccess] + self._viewport_window.visible = False # pyright: ignore [reportOptionalMemberAccess] + elif mode == RenderMode.NO_RENDERING: + # hide the viewport and disable updates + if self._viewport_context is not None: + self._viewport_context.updates_enabled = False # pyright: ignore [reportOptionalMemberAccess] + self._viewport_window.visible = False # pyright: ignore [reportOptionalMemberAccess] + # reset the throttle counter + self._render_throttle_counter = 0 + else: + raise ValueError(f"Unsupported render mode: {mode}! Please check `RenderMode` for details.") + # update render mode + self.render_mode = mode + + def reset(self, soft: bool = False) -> None: + """Reset visualizer (timeline control + warmup renders on hard reset). + + Args: + soft: If True, skip timeline reset and warmup. + """ + if self._timeline is None: + return + + if not soft: + # disable app control on stop handle during reset + self._timeline.set_stop_handle_enabled(False) + if not self.is_stopped(): + self.stop() + self._timeline.set_stop_handle_enabled(True) + # play the simulation + self.play() + # warmup renders to initialize replicator buffers + warmup_count = self.cfg.warmup_renders if hasattr(self.cfg, "warmup_renders") else 2 + for _ in range(warmup_count): + self.render() + + def close(self) -> None: + """Clean up visualizer resources.""" + # Clean up timeline control + if self._timeline is not None: + self._timeline.close() + self._timeline = None + + self._sim = None + self._app_iface = None + self._viewport_context = None + self._viewport_window = None + self._is_initialized = False + self._is_closed = True + + # ------------------------------------------------------------------ + # Private Methods + # ------------------------------------------------------------------ + + def _on_timeline_stop(self) -> None: + """Callback invoked when the simulation timeline is stopped. + + Once the simulation is stopped, the physics handles go invalid. After that, it is not possible to + resume the simulation from the last state. This leaves the app in an inconsistent state, where + two possible actions can be taken: + + 1. **Keep the app rendering**: In this case, the simulation is kept running and the app is not shutdown. + However, the physics is not updated and the script cannot be resumed from the last state. The + user has to manually close the app to stop the simulation. + 2. **Shutdown the app**: This is the default behavior. In this case, the app is shutdown and + the simulation is stopped. + + Note: + This callback is used only when running the simulation in a standalone python script. In an extension, + it is expected that the user handles the extension shutdown. + """ + # Currently a no-op, but can be extended to handle stop events + pass + + def _apply_render_settings_from_cfg(self): # noqa: C901 + """Sets rtx settings specified in the RenderCfg.""" + if self._sim is None: + return + + # define mapping of user-friendly RenderCfg names to native carb names + rendering_setting_name_mapping = { + "enable_translucency": "/rtx/translucency/enabled", + "enable_reflections": "/rtx/reflections/enabled", + "enable_global_illumination": "/rtx/indirectDiffuse/enabled", + "enable_dlssg": "/rtx-transient/dlssg/enabled", + "enable_dl_denoiser": "/rtx-transient/dldenoiser/enabled", + "dlss_mode": "/rtx/post/dlss/execMode", + "enable_direct_lighting": "/rtx/directLighting/enabled", + "samples_per_pixel": "/rtx/directLighting/sampledLighting/samplesPerPixel", + "enable_shadows": "/rtx/shadows/enabled", + "enable_ambient_occlusion": "/rtx/ambientOcclusion/enabled", + "dome_light_upper_lower_strategy": "/rtx/domeLight/upperLowerStrategy", + } + + not_carb_settings = ["rendering_mode", "carb_settings", "antialiasing_mode"] + + # grab the rendering mode using the following priority: + # 1. command line argument --rendering_mode, if provided + # 2. rendering_mode from Render Config, if set + # 3. lastly, default to "balanced" mode, if neither is specified + rendering_mode = self._sim.carb_settings.get("/isaaclab/rendering/rendering_mode") + if not rendering_mode: + rendering_mode = self._sim.cfg.render.rendering_mode + if not rendering_mode: + rendering_mode = "balanced" + + # set preset settings (same behavior as the CLI arg --rendering_mode) + if rendering_mode is not None: + # check if preset is supported + supported_rendering_modes = ["performance", "balanced", "quality"] + if rendering_mode not in supported_rendering_modes: + raise ValueError( + f"RenderCfg rendering mode '{rendering_mode}' not in supported modes {supported_rendering_modes}." + ) + + # 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 + if get_isaac_sim_version().major < 5: + isaaclab_app_exp_path = os.path.join(isaaclab_app_exp_path, "isaacsim_4_5") + + # grab preset settings + preset_filename = os.path.join(isaaclab_app_exp_path, f"rendering_modes/{rendering_mode}.kit") + with open(preset_filename) as file: + preset_dict = toml.load(file) + preset_dict = dict(flatdict.FlatDict(preset_dict, delimiter=".")) + + # set presets + for key, value in preset_dict.items(): + key = "/" + key.replace(".", "/") # convert to carb setting format + self._sim.set_setting(key, value) + + # set user-friendly named settings + for key, value in vars(self._sim.cfg.render).items(): + if value is None or key in not_carb_settings: + # skip unset settings and non-carb settings + continue + if key not in rendering_setting_name_mapping: + raise ValueError( + f"'{key}' in RenderCfg not found. Note: internal 'rendering_setting_name_mapping' dictionary might" + " need to be updated." + ) + key = rendering_setting_name_mapping[key] + self._sim.set_setting(key, value) + + # set general carb settings + carb_settings = self._sim.cfg.render.carb_settings + if carb_settings is not None: + for key, value in carb_settings.items(): + if "_" in key: + key = "/" + key.replace("_", "/") # convert from python variable style string + elif "." in key: + key = "/" + key.replace(".", "/") # convert from .kit file style string + if self._sim.get_setting(key) is None: + raise ValueError(f"'{key}' in RenderCfg.general_parameters does not map to a carb setting.") + self._sim.set_setting(key, value) + + # set denoiser mode + if self._sim.cfg.render.antialiasing_mode is not None: + try: + import omni.replicator.core as rep + + rep.settings.set_render_rtx_realtime(antialiasing=self._sim.cfg.render.antialiasing_mode) + except Exception: + pass + + # WAR: Ensure /rtx/renderMode RaytracedLighting is correctly cased. + if self._sim.carb_settings.get("/rtx/rendermode").lower() == "raytracedlighting": + self._sim.set_setting("/rtx/rendermode", "RaytracedLighting") + + def _configure_rendering_dt(self): + """Configures the rendering/timeline rate based on physics dt and render interval.""" + if self._sim is None or self._timeline is None: + return + + from pxr import Usd + + cfg = self._sim.cfg + stage = self._sim.stage + # compute rendering frequency + render_interval = max(cfg.render_interval, 1) + rendering_hz = int(1.0 / (cfg.physics_manager_cfg.dt * render_interval)) + + # If rate limiting is enabled, set the rendering rate to the specified value + # Otherwise run the app as fast as possible and do not specify the target rate + if self._sim.get_setting("/app/runLoops/main/rateLimitEnabled"): + self._sim.set_setting("/app/runLoops/main/rateLimitFrequency", rendering_hz) + self._timeline.set_target_framerate(rendering_hz) + + # set stage time codes per second + with Usd.EditContext(stage, stage.GetRootLayer()): + stage.SetTimeCodesPerSecond(rendering_hz) + self._timeline.set_time_codes_per_second(rendering_hz) + + # The isaac sim loop runner is enabled by default in isaac sim apps, + # but in case we are in an app with the kit loop runner, protect against this + try: + import omni.kit.loop._loop as omni_loop + + _loop_runner = omni_loop.acquire_loop_interface() + _loop_runner.set_manual_step_size(cfg.physics_manager_cfg.dt * render_interval) + _loop_runner.set_manual_mode(True) + except Exception: + logger.warning( + "Isaac Sim loop runner not found, enabling rate limiting to support rendering at specified rate" + ) + self._sim.set_setting("/app/runLoops/main/rateLimitEnabled", True) + self._sim.set_setting("/app/runLoops/main/rateLimitFrequency", rendering_hz) + self._timeline.set_target_framerate(rendering_hz) diff --git a/source/isaaclab_physx/isaaclab_physx/visualizers/physx_ov_visualizer_cfg.py b/source/isaaclab_physx/isaaclab_physx/visualizers/physx_ov_visualizer_cfg.py new file mode 100644 index 00000000000..7243118e0e5 --- /dev/null +++ b/source/isaaclab_physx/isaaclab_physx/visualizers/physx_ov_visualizer_cfg.py @@ -0,0 +1,83 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Configuration for Omniverse visualizer in PhysX-based SimulationContext.""" + +from __future__ import annotations + +from typing import TYPE_CHECKING + +from isaaclab.utils import configclass +from isaaclab.visualizers import VisualizerCfg + +from .physx_ov_visualizer import RenderMode + +if TYPE_CHECKING: + from .physx_ov_visualizer import PhysxOVVisualizer + + +@configclass +class PhysxOVVisualizerCfg(VisualizerCfg): + """Configuration for Omniverse visualizer in PhysX-based SimulationContext. + + This configuration extends :class:`VisualizerCfg` and is used by the + :class:`PhysxOVVisualizer` class which manages viewport/rendering for + PhysX-based SimulationContext workflows. + """ + + visualizer_type: str = "omniverse" + """Type identifier for Omniverse visualizer.""" + + default_render_mode: RenderMode | None = None + """Default render mode for the visualizer. + + If None, the render mode will be automatically determined based on GUI availability: + - NO_GUI_OR_RENDERING: When no GUI and offscreen rendering is disabled + - PARTIAL_RENDERING: When no GUI but offscreen rendering is enabled + - FULL_RENDERING: When GUI is available (local, livestreamed, or XR) + + See :class:`RenderMode` for available options. + """ + + render_throttle_period: int = 5 + """Throttle period for rendering updates. + + This controls how frequently UI elements are updated when in NO_RENDERING mode. + A higher value means less frequent UI updates, improving performance. + """ + + camera_prim_path: str = "/OmniverseKit_Persp" + """Path to the camera primitive in the USD stage.""" + + warmup_renders: int = 2 + """Number of warmup renders to perform on hard reset. + + This is used to initialize replicator buffers before the simulation starts. + """ + + viewport_name: str | None = "Viewport" + """Viewport name to use. If None, uses active viewport.""" + + create_viewport: bool = False + """Create new viewport with specified name and camera pose.""" + + dock_position: str = "SAME" + """Dock position for new viewport. Options: 'LEFT', 'RIGHT', 'BOTTOM', 'SAME' (tabs with existing).""" + + window_width: int = 1280 + """Viewport width in pixels.""" + + window_height: int = 720 + """Viewport height in pixels.""" + + def create_visualizer(self) -> "PhysxOVVisualizer": + """Create PhysxOVVisualizer instance from this config. + + Returns: + PhysxOVVisualizer instance configured with this config. + """ + from .physx_ov_visualizer import PhysxOVVisualizer + + return PhysxOVVisualizer(self) diff --git a/source/isaaclab_physx/test/sensors/check_contact_sensor.py b/source/isaaclab_physx/test/sensors/check_contact_sensor.py index b4fe5f555dc..c007c354279 100644 --- a/source/isaaclab_physx/test/sensors/check_contact_sensor.py +++ b/source/isaaclab_physx/test/sensors/check_contact_sensor.py @@ -40,6 +40,7 @@ import isaaclab.sim as sim_utils from isaaclab.assets import Articulation +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sensors.contact_sensor import ContactSensor, ContactSensorCfg from isaaclab.sim import SimulationCfg, SimulationContext from isaaclab.utils.timer import Timer @@ -74,7 +75,7 @@ def main(): """Spawns the ANYmal robot and clones it using Isaac Sim Cloner API.""" # Load kit helper - sim = SimulationContext(SimulationCfg(dt=0.005)) + sim = SimulationContext(SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.005))) # Set main camera sim.set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0]) diff --git a/source/isaaclab_physx/test/sensors/test_contact_sensor.py b/source/isaaclab_physx/test/sensors/test_contact_sensor.py index 468047201ef..e694fd51f05 100644 --- a/source/isaaclab_physx/test/sensors/test_contact_sensor.py +++ b/source/isaaclab_physx/test/sensors/test_contact_sensor.py @@ -28,6 +28,7 @@ from isaaclab.assets import RigidObject, RigidObjectCfg from isaaclab.scene import InteractiveScene, InteractiveSceneCfg from isaaclab.sensors import ContactSensor, ContactSensorCfg +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sim import SimulationCfg, SimulationContext, build_simulation_context from isaaclab.sim.utils.stage import get_current_stage from isaaclab.terrains import HfRandomUniformTerrainCfg, TerrainGeneratorCfg, TerrainImporterCfg @@ -452,7 +453,7 @@ def test_friction_reporting(setup_simulation, grav_dir): sim_dt, _, _, _, carb_settings_iface = setup_simulation carb_settings_iface.set_bool("/physics/disableContactProcessing", True) device = "cuda:0" - sim_cfg = SimulationCfg(dt=sim_dt, device=device, gravity=grav_dir) + sim_cfg = SimulationCfg(device=device, physics_manager_cfg=PhysxManagerCfg(dt=sim_dt, gravity=grav_dir)) with build_simulation_context(sim_cfg=sim_cfg, add_lighting=False) as sim: sim._app_control_on_stop_handle = None @@ -505,7 +506,7 @@ def test_invalid_prim_paths_config(setup_simulation): sim_dt, _, _, _, carb_settings_iface = setup_simulation carb_settings_iface.set_bool("/physics/disableContactProcessing", True) device = "cuda:0" - sim_cfg = SimulationCfg(dt=sim_dt, device=device) + sim_cfg = SimulationCfg(device=device, physics_manager_cfg=PhysxManagerCfg(dt=sim_dt)) with build_simulation_context(sim_cfg=sim_cfg, add_lighting=False) as sim: sim._app_control_on_stop_handle = None @@ -539,7 +540,7 @@ def test_invalid_max_contact_points_config(setup_simulation): sim_dt, _, _, _, carb_settings_iface = setup_simulation carb_settings_iface.set_bool("/physics/disableContactProcessing", True) device = "cuda:0" - sim_cfg = SimulationCfg(dt=sim_dt, device=device) + sim_cfg = SimulationCfg(device=device, physics_manager_cfg=PhysxManagerCfg(dt=sim_dt)) with build_simulation_context(sim_cfg=sim_cfg, add_lighting=False) as sim: sim._app_control_on_stop_handle = None diff --git a/source/isaaclab_physx/test/sensors/test_frame_transformer.py b/source/isaaclab_physx/test/sensors/test_frame_transformer.py index 68715581d99..e077158041e 100644 --- a/source/isaaclab_physx/test/sensors/test_frame_transformer.py +++ b/source/isaaclab_physx/test/sensors/test_frame_transformer.py @@ -21,6 +21,7 @@ import isaaclab.sim as sim_utils import isaaclab.utils.math as math_utils from isaaclab.assets import RigidObjectCfg +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.scene import InteractiveScene, InteractiveSceneCfg from isaaclab.sensors import FrameTransformerCfg, OffsetCfg from isaaclab.terrains import TerrainImporterCfg @@ -77,7 +78,7 @@ def sim(): # Create a new stage sim_utils.create_new_stage() # Load kit helper - sim = sim_utils.SimulationContext(sim_utils.SimulationCfg(dt=0.005, device="cpu")) + sim = sim_utils.SimulationContext(sim_utils.SimulationCfg(device="cpu", physics_manager_cfg=PhysxManagerCfg(dt=0.005))) # Set main camera sim.set_camera_view(eye=(5.0, 5.0, 5.0), target=(0.0, 0.0, 0.0)) yield sim diff --git a/source/isaaclab_physx/test/sensors/test_imu.py b/source/isaaclab_physx/test/sensors/test_imu.py index 2120bd6f712..77bc497a61c 100644 --- a/source/isaaclab_physx/test/sensors/test_imu.py +++ b/source/isaaclab_physx/test/sensors/test_imu.py @@ -23,6 +23,7 @@ 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_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.scene import InteractiveScene, InteractiveSceneCfg from isaaclab.sensors.imu import Imu, ImuCfg from isaaclab.terrains import TerrainImporterCfg @@ -204,8 +205,7 @@ def setup_sim(): # Create a new stage sim_utils.create_new_stage() # Load simulation context - sim_cfg = sim_utils.SimulationCfg(dt=0.001) - sim_cfg.physx.solver_type = 0 # 0: PGS, 1: TGS --> use PGS for more accurate results + sim_cfg = sim_utils.SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.001, solver_type=0)) # 0: PGS, 1: TGS --> use PGS for more accurate results sim = sim_utils.SimulationContext(sim_cfg) # construct scene scene_cfg = MySceneCfg(num_envs=2, env_spacing=5.0, lazy_sensor_update=False) diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/allegro_hand/allegro_hand_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/direct/allegro_hand/allegro_hand_env_cfg.py index ee6e1fdeea7..dc900075d63 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/allegro_hand/allegro_hand_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/allegro_hand/allegro_hand_env_cfg.py @@ -9,7 +9,8 @@ from isaaclab.envs import DirectRLEnvCfg from isaaclab.markers import VisualizationMarkersCfg from isaaclab.scene import InteractiveSceneCfg -from isaaclab.sim import PhysxCfg, SimulationCfg +from isaaclab.sim import SimulationCfg +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sim.spawners.materials.physics_materials_cfg import RigidBodyMaterialCfg from isaaclab.utils import configclass from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR @@ -29,13 +30,13 @@ class AllegroHandEnvCfg(DirectRLEnvCfg): obs_type = "full" # simulation sim: SimulationCfg = SimulationCfg( - dt=1 / 120, render_interval=decimation, - physics_material=RigidBodyMaterialCfg( - static_friction=1.0, - dynamic_friction=1.0, - ), - physx=PhysxCfg( + physics_manager_cfg=PhysxManagerCfg( + dt=1 / 120, + physics_material=RigidBodyMaterialCfg( + static_friction=1.0, + dynamic_friction=1.0, + ), bounce_threshold_velocity=0.2, ), ) diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/ant/ant_env.py b/source/isaaclab_tasks/isaaclab_tasks/direct/ant/ant_env.py index 39ae57b2967..cd509e5d4d3 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/ant/ant_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/ant/ant_env.py @@ -8,6 +8,7 @@ import isaaclab.sim as sim_utils from isaaclab.assets import ArticulationCfg from isaaclab.envs import DirectRLEnvCfg +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.scene import InteractiveSceneCfg from isaaclab.sim import SimulationCfg from isaaclab.terrains import TerrainImporterCfg @@ -29,7 +30,7 @@ class AntEnvCfg(DirectRLEnvCfg): state_space = 0 # simulation - sim: SimulationCfg = SimulationCfg(dt=1 / 120, render_interval=decimation) + sim: SimulationCfg = SimulationCfg(render_interval=decimation, physics_manager_cfg=PhysxManagerCfg(dt=1 / 120)) terrain = TerrainImporterCfg( prim_path="/World/ground", terrain_type="plane", diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/automate/disassembly_env.py b/source/isaaclab_tasks/isaaclab_tasks/direct/automate/disassembly_env.py index 05c20fc0a2e..41cf740c327 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/automate/disassembly_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/automate/disassembly_env.py @@ -568,7 +568,7 @@ def _move_gripper_to_eef_pose(self, env_ids, goal_pos, goal_quat, sim_steps, if_ self.actions *= 0.0 self.actions[env_ids, :6] = delta_hand_pose - is_rendering = self.sim.has_gui() or self.sim.has_rtx_sensors() + is_rendering = self.sim.carb_settings.get("/isaaclab/has_gui") or self.sim.has_rtx_sensors() # perform physics stepping for _ in range(self.cfg.decimation): self._sim_step_counter += 1 diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/cart_double_pendulum/cart_double_pendulum_env.py b/source/isaaclab_tasks/isaaclab_tasks/direct/cart_double_pendulum/cart_double_pendulum_env.py index e0464a7201c..b07619f0e6a 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/cart_double_pendulum/cart_double_pendulum_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/cart_double_pendulum/cart_double_pendulum_env.py @@ -13,6 +13,7 @@ import isaaclab.sim as sim_utils from isaaclab.assets import Articulation, ArticulationCfg from isaaclab.envs import DirectMARLEnv, DirectMARLEnvCfg +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.scene import InteractiveSceneCfg from isaaclab.sim import SimulationCfg from isaaclab.sim.spawners.from_files import GroundPlaneCfg, spawn_ground_plane @@ -33,7 +34,7 @@ class CartDoublePendulumEnvCfg(DirectMARLEnvCfg): state_space = -1 # simulation - sim: SimulationCfg = SimulationCfg(dt=1 / 120, render_interval=decimation) + sim: SimulationCfg = SimulationCfg(render_interval=decimation, physics_manager_cfg=PhysxManagerCfg(dt=1 / 120)) # robot robot_cfg: ArticulationCfg = CART_DOUBLE_PENDULUM_CFG.replace(prim_path="/World/envs/env_.*/Robot") diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/cartpole/cartpole_camera_env.py b/source/isaaclab_tasks/isaaclab_tasks/direct/cartpole/cartpole_camera_env.py index d22412f9415..d44877b802e 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/cartpole/cartpole_camera_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/cartpole/cartpole_camera_env.py @@ -13,6 +13,7 @@ import isaaclab.sim as sim_utils from isaaclab.assets import Articulation, ArticulationCfg from isaaclab.envs import DirectRLEnv, DirectRLEnvCfg, ViewerCfg +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.scene import InteractiveSceneCfg from isaaclab.sensors import TiledCamera, TiledCameraCfg, save_images_to_file from isaaclab.sim import SimulationCfg @@ -30,7 +31,7 @@ class CartpoleRGBCameraEnvCfg(DirectRLEnvCfg): action_scale = 100.0 # [N] # simulation - sim: SimulationCfg = SimulationCfg(dt=1 / 120, render_interval=decimation) + sim: SimulationCfg = SimulationCfg(render_interval=decimation, physics_manager_cfg=PhysxManagerCfg(dt=1 / 120)) # robot robot_cfg: ArticulationCfg = CARTPOLE_CFG.replace(prim_path="/World/envs/env_.*/Robot") diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/cartpole/cartpole_env.py b/source/isaaclab_tasks/isaaclab_tasks/direct/cartpole/cartpole_env.py index f897b64f3ec..634b9734175 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/cartpole/cartpole_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/cartpole/cartpole_env.py @@ -13,6 +13,7 @@ import isaaclab.sim as sim_utils from isaaclab.assets import Articulation, ArticulationCfg from isaaclab.envs import DirectRLEnv, DirectRLEnvCfg +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.scene import InteractiveSceneCfg from isaaclab.sim import SimulationCfg from isaaclab.sim.spawners.from_files import GroundPlaneCfg, spawn_ground_plane @@ -33,7 +34,7 @@ class CartpoleEnvCfg(DirectRLEnvCfg): state_space = 0 # simulation - sim: SimulationCfg = SimulationCfg(dt=1 / 120, render_interval=decimation) + sim: SimulationCfg = SimulationCfg(render_interval=decimation, physics_manager_cfg=PhysxManagerCfg(dt=1 / 120)) # robot robot_cfg: ArticulationCfg = CARTPOLE_CFG.replace(prim_path="/World/envs/env_.*/Robot") diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/humanoid/humanoid_env.py b/source/isaaclab_tasks/isaaclab_tasks/direct/humanoid/humanoid_env.py index 402409e9d35..13ad914fdf2 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/humanoid/humanoid_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/humanoid/humanoid_env.py @@ -8,6 +8,7 @@ import isaaclab.sim as sim_utils from isaaclab.assets import ArticulationCfg from isaaclab.envs import DirectRLEnvCfg +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.scene import InteractiveSceneCfg from isaaclab.sim import SimulationCfg from isaaclab.terrains import TerrainImporterCfg @@ -29,7 +30,7 @@ class HumanoidEnvCfg(DirectRLEnvCfg): state_space = 0 # simulation - sim: SimulationCfg = SimulationCfg(dt=1 / 120, render_interval=decimation) + sim: SimulationCfg = SimulationCfg(render_interval=decimation, physics_manager_cfg=PhysxManagerCfg(dt=1 / 120)) terrain = TerrainImporterCfg( prim_path="/World/ground", terrain_type="plane", diff --git a/tools/template/templates/tasks/direct_multi-agent/env_cfg b/tools/template/templates/tasks/direct_multi-agent/env_cfg index 3b207209b73..5cd81020413 100644 --- a/tools/template/templates/tasks/direct_multi-agent/env_cfg +++ b/tools/template/templates/tasks/direct_multi-agent/env_cfg @@ -7,6 +7,7 @@ from isaaclab_assets.robots.cart_double_pendulum import CART_DOUBLE_PENDULUM_CFG from isaaclab.assets import ArticulationCfg from isaaclab.envs import DirectMARLEnvCfg +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.scene import InteractiveSceneCfg from isaaclab.sim import SimulationCfg from isaaclab.utils import configclass @@ -24,7 +25,7 @@ class {{ task.classname }}EnvCfg(DirectMARLEnvCfg): state_space = -1 # simulation - sim: SimulationCfg = SimulationCfg(dt=1 / 120, render_interval=decimation) + sim: SimulationCfg = SimulationCfg(render_interval=decimation, physics_manager_cfg=PhysxManagerCfg(dt=1 / 120)) # robot(s) robot_cfg: ArticulationCfg = CART_DOUBLE_PENDULUM_CFG.replace(prim_path="/World/envs/env_.*/Robot") diff --git a/tools/template/templates/tasks/direct_single-agent/env_cfg b/tools/template/templates/tasks/direct_single-agent/env_cfg index 10588cd3e84..8a794ff1af9 100644 --- a/tools/template/templates/tasks/direct_single-agent/env_cfg +++ b/tools/template/templates/tasks/direct_single-agent/env_cfg @@ -7,6 +7,7 @@ from isaaclab_assets.robots.cartpole import CARTPOLE_CFG from isaaclab.assets import ArticulationCfg from isaaclab.envs import DirectRLEnvCfg +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.scene import InteractiveSceneCfg from isaaclab.sim import SimulationCfg from isaaclab.utils import configclass @@ -23,7 +24,7 @@ class {{ task.classname }}EnvCfg(DirectRLEnvCfg): state_space = 0 # simulation - sim: SimulationCfg = SimulationCfg(dt=1 / 120, render_interval=decimation) + sim: SimulationCfg = SimulationCfg(render_interval=decimation, physics_manager_cfg=PhysxManagerCfg(dt=1 / 120)) # robot(s) robot_cfg: ArticulationCfg = CARTPOLE_CFG.replace(prim_path="/World/envs/env_.*/Robot") From f1eb48ca9909c31ba18389063c4125f4f50b52b9 Mon Sep 17 00:00:00 2001 From: Octi Zhang Date: Fri, 6 Feb 2026 11:37:28 -0800 Subject: [PATCH 02/46] fixed some bug and added deprecation cycle --- .../isaaclab/envs/ui/base_env_window.py | 2 +- .../isaaclab/isaaclab/sim/simulation_cfg.py | 99 ++++++++++++++++++- .../isaaclab/sim/simulation_context.py | 4 - 3 files changed, 99 insertions(+), 6 deletions(-) diff --git a/source/isaaclab/isaaclab/envs/ui/base_env_window.py b/source/isaaclab/isaaclab/envs/ui/base_env_window.py index a0760f9b011..e0f2e122911 100644 --- a/source/isaaclab/isaaclab/envs/ui/base_env_window.py +++ b/source/isaaclab/isaaclab/envs/ui/base_env_window.py @@ -139,7 +139,7 @@ def _build_sim_frame(self): **record_animate_cfg ) # disable the button if fabric is not enabled - self.ui_window_elements["record_animation"].enabled = not self.env.sim.is_fabric_enabled() + self.ui_window_elements["record_animation"].enabled = not self.env.sim.get_setting("/isaaclab/fabric_enabled") def _build_viewer_frame(self): """Build the viewer-related control frame for the UI.""" diff --git a/source/isaaclab/isaaclab/sim/simulation_cfg.py b/source/isaaclab/isaaclab/sim/simulation_cfg.py index ca6bb8f9078..503fde222ea 100644 --- a/source/isaaclab/isaaclab/sim/simulation_cfg.py +++ b/source/isaaclab/isaaclab/sim/simulation_cfg.py @@ -9,6 +9,7 @@ configuring the environment instances, viewer settings, and simulation parameters. """ +import warnings from typing import Any, Literal # Literal used by RenderCfg from isaaclab.utils import configclass @@ -18,6 +19,17 @@ from isaaclab.visualizers import VisualizerCfg +# Mapping of deprecated SimulationCfg fields to their new location in physics_manager_cfg +_DEPRECATED_FIELDS = { + "dt": "physics_manager_cfg.dt", + "gravity": "physics_manager_cfg.gravity", + "physics_prim_path": "physics_manager_cfg.physics_prim_path", + "physics_material": "physics_manager_cfg.physics_material", + "use_fabric": "physics_manager_cfg.use_fabric", + "physx": "physics_manager_cfg (PhysxManagerCfg attributes directly)", +} + + @configclass class RenderCfg: """Configuration for Omniverse RTX Renderer. @@ -165,7 +177,21 @@ class RenderCfg: @configclass class SimulationCfg: - """Configuration for simulation physics.""" + """Configuration for simulation physics. + + .. note:: + The following fields have been moved to ``physics_manager_cfg`` and are deprecated: + + - ``dt`` → ``physics_manager_cfg.dt`` + - ``gravity`` → ``physics_manager_cfg.gravity`` + - ``physics_prim_path`` → ``physics_manager_cfg.physics_prim_path`` + - ``physics_material`` → ``physics_manager_cfg.physics_material`` + - ``use_fabric`` → ``physics_manager_cfg.use_fabric`` + - ``physx`` → Use ``PhysxManagerCfg`` attributes directly + + Using the old field names will issue a deprecation warning and forward + the values to the new location. + """ device: str = "cuda:0" """The device to run the simulation on. Default is ``"cuda:0"``. @@ -226,3 +252,74 @@ class SimulationCfg: visualizer_cfgs: list[VisualizerCfg] | VisualizerCfg | None = None """The list of visualizer configurations. Default is None.""" + + def __setattr__(self, name: str, value: Any) -> None: + """Intercept deprecated attribute assignment and forward to physics_manager_cfg.""" + # Mapping of deprecated fields to their new location + deprecated_map = { + "dt": "physics_manager_cfg.dt", + "gravity": "physics_manager_cfg.gravity", + "physics_prim_path": "physics_manager_cfg.physics_prim_path", + "physics_material": "physics_manager_cfg.physics_material", + "use_fabric": "physics_manager_cfg.use_fabric", + } + + if name in deprecated_map: + # Check if physics_manager_cfg is already set (avoid recursion during init) + try: + physics_cfg = object.__getattribute__(self, "physics_manager_cfg") + if hasattr(physics_cfg, name): + setattr(physics_cfg, name, value) + warnings.warn( + f"SimulationCfg.{name} is deprecated. " + f"Use {deprecated_map[name]} instead.", + DeprecationWarning, + stacklevel=2, + ) + return + except AttributeError: + # physics_manager_cfg not yet set, fall through to normal setattr + pass + # Default behavior + object.__setattr__(self, name, value) + + def __getattr__(self, name: str) -> Any: + """Intercept deprecated attribute access and forward to physics_manager_cfg.""" + # Mapping of deprecated fields to their new location + deprecated_map = { + "dt": "physics_manager_cfg.dt", + "gravity": "physics_manager_cfg.gravity", + "physics_prim_path": "physics_manager_cfg.physics_prim_path", + "physics_material": "physics_manager_cfg.physics_material", + "use_fabric": "physics_manager_cfg.use_fabric", + } + + if name in deprecated_map: + try: + physics_cfg = object.__getattribute__(self, "physics_manager_cfg") + if hasattr(physics_cfg, name): + warnings.warn( + f"SimulationCfg.{name} is deprecated. " + f"Use {deprecated_map[name]} instead.", + DeprecationWarning, + stacklevel=2, + ) + return getattr(physics_cfg, name) + except AttributeError: + pass + + # Provide access to 'physx' as a proxy to physics_manager_cfg for PhysX settings + if name == "physx": + try: + physics_cfg = object.__getattribute__(self, "physics_manager_cfg") + warnings.warn( + "SimulationCfg.physx is deprecated. Set PhysX attributes " + "directly on physics_manager_cfg (PhysxManagerCfg).", + DeprecationWarning, + stacklevel=2, + ) + return physics_cfg + except AttributeError: + pass + + raise AttributeError(f"'{type(self).__name__}' object has no attribute '{name}'") diff --git a/source/isaaclab/isaaclab/sim/simulation_context.py b/source/isaaclab/isaaclab/sim/simulation_context.py index f2aca3fcc7c..d6abb0beab9 100644 --- a/source/isaaclab/isaaclab/sim/simulation_context.py +++ b/source/isaaclab/isaaclab/sim/simulation_context.py @@ -160,10 +160,6 @@ def physics_sim_view(self): """Returns the physics simulation view.""" return self.physics_manager.get_physics_sim_view() - def is_fabric_enabled(self) -> bool: - """Returns whether the fabric interface is enabled.""" - return self.carb_settings.get_as_bool("/isaaclab/fabric_enabled") - def get_physics_dt(self) -> float: """Returns the physics time step.""" return self.physics_manager.get_physics_dt() From 3f15770a18523344a7691138efa9d080b450e7fe Mon Sep 17 00:00:00 2001 From: Octi Zhang Date: Fri, 6 Feb 2026 17:15:33 -0800 Subject: [PATCH 03/46] save --- .../isaaclab/physics/physics_manager.py | 1 + .../isaaclab/physics/physics_manager_cfg.py | 10 - source/isaaclab/isaaclab/sim/__init__.py | 22 + .../isaaclab/isaaclab/sim/simulation_cfg.py | 143 ++- .../isaaclab/sim/simulation_context.py | 17 +- .../isaaclab/test/sensors/test_sensor_base.py | 7 +- .../test_build_simulation_context_headless.py | 19 +- ...st_build_simulation_context_nonheadless.py | 24 +- .../test/sim/test_simulation_context.py | 1073 +++++++++++++++-- .../isaaclab_physx/isaaclab_physx/__init__.py | 18 + 10 files changed, 1195 insertions(+), 139 deletions(-) diff --git a/source/isaaclab/isaaclab/physics/physics_manager.py b/source/isaaclab/isaaclab/physics/physics_manager.py index df4148caa3b..3d23cd6a148 100644 --- a/source/isaaclab/isaaclab/physics/physics_manager.py +++ b/source/isaaclab/isaaclab/physics/physics_manager.py @@ -257,6 +257,7 @@ def initialize(cls, sim_context: "SimulationContext") -> None: # regardless of which subclass is active (Python class vars are per-class) PhysicsManager._sim = sim_context PhysicsManager._cfg = sim_context.cfg.physics_manager_cfg + PhysicsManager._device = sim_context.cfg.device PhysicsManager._sim_time = 0.0 @classmethod diff --git a/source/isaaclab/isaaclab/physics/physics_manager_cfg.py b/source/isaaclab/isaaclab/physics/physics_manager_cfg.py index 2f38eb703e6..d898a4769d8 100644 --- a/source/isaaclab/isaaclab/physics/physics_manager_cfg.py +++ b/source/isaaclab/isaaclab/physics/physics_manager_cfg.py @@ -36,16 +36,6 @@ class PhysicsManagerCfg: dt: float = 1.0 / 60.0 """The physics simulation time-step (in seconds). Default is 0.0167 seconds.""" - device: str = "cuda:0" - """The device to run the simulation on. Default is ``"cuda:0"``. - - Valid options are: - - - ``"cpu"``: Use CPU. - - ``"cuda"``: Use GPU, where the device ID is inferred from config. - - ``"cuda:N"``: Use GPU, where N is the device ID. For example, "cuda:0". - """ - gravity: tuple[float, float, float] = (0.0, 0.0, -9.81) """The gravity vector (in m/s^2). Default is (0.0, 0.0, -9.81).""" diff --git a/source/isaaclab/isaaclab/sim/__init__.py b/source/isaaclab/isaaclab/sim/__init__.py index ea3b3c7c82e..3d8a73c28e9 100644 --- a/source/isaaclab/isaaclab/sim/__init__.py +++ b/source/isaaclab/isaaclab/sim/__init__.py @@ -26,6 +26,8 @@ """ +import warnings + from .converters import * # noqa: F401, F403 from .schemas import * # noqa: F401, F403 from .simulation_cfg import RenderCfg, SimulationCfg # noqa: F401, F403 @@ -33,3 +35,23 @@ from .spawners import * # noqa: F401, F403 from .utils import * # noqa: F401, F403 from .views import * # noqa: F401, F403 + +# Deprecated alias for PhysxCfg -> PhysxManagerCfg +# This supports old code that uses `from isaaclab.sim import PhysxCfg` +try: + from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg as _PhysxManagerCfg + + class PhysxCfg(_PhysxManagerCfg): + """DEPRECATED: Use PhysxManagerCfg from isaaclab_physx.physics instead.""" + + def __init__(self, *args, **kwargs): + warnings.warn( + "PhysxCfg is deprecated. Use PhysxManagerCfg from isaaclab_physx.physics instead.", + DeprecationWarning, + stacklevel=2, + ) + super().__init__(*args, **kwargs) + +except ImportError: + # isaaclab_physx not installed + PhysxCfg = None # type: ignore diff --git a/source/isaaclab/isaaclab/sim/simulation_cfg.py b/source/isaaclab/isaaclab/sim/simulation_cfg.py index 503fde222ea..b6a869b3e8f 100644 --- a/source/isaaclab/isaaclab/sim/simulation_cfg.py +++ b/source/isaaclab/isaaclab/sim/simulation_cfg.py @@ -19,6 +19,20 @@ from isaaclab.visualizers import VisualizerCfg +# Deprecated alias for PhysxCfg -> PhysxManagerCfg +# This supports old code that uses `from isaaclab.sim.simulation_cfg import PhysxCfg` +class PhysxCfg(PhysxManagerCfg): + """DEPRECATED: Use PhysxManagerCfg from isaaclab_physx.physics instead.""" + + def __init__(self, *args, **kwargs): + warnings.warn( + "PhysxCfg is deprecated. Use PhysxManagerCfg from isaaclab_physx.physics instead.", + DeprecationWarning, + stacklevel=2, + ) + super().__init__(*args, **kwargs) + + # Mapping of deprecated SimulationCfg fields to their new location in physics_manager_cfg _DEPRECATED_FIELDS = { "dt": "physics_manager_cfg.dt", @@ -253,6 +267,116 @@ class SimulationCfg: visualizer_cfgs: list[VisualizerCfg] | VisualizerCfg | None = None """The list of visualizer configurations. Default is None.""" + # Deprecated fields - accepted in constructor for backward compatibility + dt: float | None = None + """DEPRECATED: Use physics_manager_cfg.dt instead.""" + + gravity: tuple[float, float, float] | None = None + """DEPRECATED: Use physics_manager_cfg.gravity instead.""" + + physics_prim_path: str | None = None + """DEPRECATED: Use physics_manager_cfg.physics_prim_path instead.""" + + physics_material: Any | None = None + """DEPRECATED: Use physics_manager_cfg.physics_material instead.""" + + use_fabric: bool | None = None + """DEPRECATED: Use physics_manager_cfg.use_fabric instead.""" + + physx: Any | None = None + """DEPRECATED: Use physics_manager_cfg (PhysxManagerCfg) directly instead. + + After initialization, this field is set to physics_manager_cfg for backward compatibility. + """ + + def __post_init__(self): + """Forward deprecated constructor arguments to physics_manager_cfg.""" + deprecated_fields = ["dt", "gravity", "physics_prim_path", "physics_material", "use_fabric"] + + for field_name in deprecated_fields: + # Use getattr with None default - field might not exist during class definition + value = getattr(self, field_name, None) + if value is not None: + warnings.warn( + f"SimulationCfg({field_name}=...) is deprecated. " + f"Use SimulationCfg(physics_manager_cfg=PhysxManagerCfg({field_name}=...)) instead.", + DeprecationWarning, + stacklevel=4, + ) + # Forward to physics_manager_cfg + if hasattr(self.physics_manager_cfg, field_name): + setattr(self.physics_manager_cfg, field_name, value) + + # Delete deprecated fields so __getattr__ is called when accessing them + # This allows runtime access like self.sim.dt to work via __getattr__ + for field_name in deprecated_fields: + if field_name != "physics_material": # physics_material needs object access + try: + delattr(self, field_name) + except AttributeError: + pass + + # Set physics_material to point to physics_manager_cfg.physics_material for backward-compatible access + if hasattr(self.physics_manager_cfg, "physics_material"): + object.__setattr__(self, "physics_material", self.physics_manager_cfg.physics_material) + + # Handle physx=PhysxCfg(...) - copy PhysX-specific attributes to physics_manager_cfg + # The old PhysxCfg only had PhysX-specific settings, not dt/gravity/etc. + physx_cfg = getattr(self, "physx", None) + if physx_cfg is not None: + warnings.warn( + "SimulationCfg(physx=...) is deprecated. " + "Use SimulationCfg(physics_manager_cfg=PhysxManagerCfg(...)) instead.", + DeprecationWarning, + stacklevel=4, + ) + # PhysX-specific fields that should be copied (not general physics settings) + physx_specific_fields = { + "bounce_threshold_velocity", + "friction_offset_threshold", + "friction_correlation_distance", + "solver_type", + "enable_stabilization", + "max_depenetration_velocity", + "enable_enhanced_determinism", + "min_position_iteration_count", + "max_position_iteration_count", + "min_velocity_iteration_count", + "max_velocity_iteration_count", + "enable_ccd", + "gpu_max_rigid_contact_count", + "gpu_max_rigid_patch_count", + "gpu_found_lost_pairs_capacity", + "gpu_found_lost_aggregate_pairs_capacity", + "gpu_total_aggregate_pairs_capacity", + "gpu_heap_capacity", + "gpu_temp_buffer_capacity", + "gpu_max_num_partitions", + "gpu_max_soft_body_contacts", + "gpu_max_particle_contacts", + "gpu_collision_stack_size", + } + + import dataclasses + + if dataclasses.is_dataclass(physx_cfg): + for field in dataclasses.fields(physx_cfg): + if field.name in physx_specific_fields: + value = getattr(physx_cfg, field.name) + # Get field default + if field.default is not dataclasses.MISSING: + default = field.default + elif field.default_factory is not dataclasses.MISSING: + default = field.default_factory() + else: + default = None + # Only copy if different from default + if value != default and hasattr(self.physics_manager_cfg, field.name): + setattr(self.physics_manager_cfg, field.name, value) + + # Set physx to physics_manager_cfg for backward-compatible access (sim.physx.some_setting) + object.__setattr__(self, "physx", self.physics_manager_cfg) + def __setattr__(self, name: str, value: Any) -> None: """Intercept deprecated attribute assignment and forward to physics_manager_cfg.""" # Mapping of deprecated fields to their new location @@ -264,8 +388,8 @@ def __setattr__(self, name: str, value: Any) -> None: "use_fabric": "physics_manager_cfg.use_fabric", } - if name in deprecated_map: - # Check if physics_manager_cfg is already set (avoid recursion during init) + if name in deprecated_map and value is not None: + # Only forward non-None values (None means "not set" for deprecated fields) try: physics_cfg = object.__getattribute__(self, "physics_manager_cfg") if hasattr(physics_cfg, name): @@ -308,18 +432,7 @@ def __getattr__(self, name: str) -> Any: except AttributeError: pass - # Provide access to 'physx' as a proxy to physics_manager_cfg for PhysX settings - if name == "physx": - try: - physics_cfg = object.__getattribute__(self, "physics_manager_cfg") - warnings.warn( - "SimulationCfg.physx is deprecated. Set PhysX attributes " - "directly on physics_manager_cfg (PhysxManagerCfg).", - DeprecationWarning, - stacklevel=2, - ) - return physics_cfg - except AttributeError: - pass + # Note: 'physx' is now a field set to physics_manager_cfg in __post_init__ + # for backward compatibility with sim.physx.some_setting access raise AttributeError(f"'{type(self).__name__}' object has no attribute '{name}'") diff --git a/source/isaaclab/isaaclab/sim/simulation_context.py b/source/isaaclab/isaaclab/sim/simulation_context.py index d6abb0beab9..572a63aaf8d 100644 --- a/source/isaaclab/isaaclab/sim/simulation_context.py +++ b/source/isaaclab/isaaclab/sim/simulation_context.py @@ -90,7 +90,6 @@ def __init__(self, cfg: SimulationCfg | None = None): # Store config self.cfg = SimulationCfg() if cfg is None else cfg - self.device = self.cfg.device # Get existing stage or create new one in memory stage_cache = UsdUtils.StageCache.Get() @@ -144,7 +143,7 @@ def _init_usd_physics_scene(self) -> None: physics_scene = UsdPhysics.Scene.Define(self.stage, cfg.physics_prim_path) # Pre-create gravity tensor to avoid torch heap corruption issues (torch 2.1+) - gravity = torch.tensor(cfg.gravity, dtype=torch.float32, device=cfg.device) + gravity = torch.tensor(cfg.gravity, dtype=torch.float32, device=self.cfg.device) gravity_magnitude = torch.norm(gravity).item() if gravity_magnitude == 0.0: @@ -160,6 +159,16 @@ def physics_sim_view(self): """Returns the physics simulation view.""" return self.physics_manager.get_physics_sim_view() + @property + def device(self) -> str: + """Returns the device on which the simulation is running.""" + return self.physics_manager.get_device() + + @property + def backend(self) -> str: + """Returns the tensor backend being used ("numpy" or "torch").""" + return self.physics_manager.get_backend() + def get_physics_dt(self) -> float: """Returns the physics time step.""" return self.physics_manager.get_physics_dt() @@ -363,8 +372,8 @@ def build_simulation_context( from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg gravity = (0.0, 0.0, -9.81) if gravity_enabled else (0.0, 0.0, 0.0) - physics_manager_cfg = PhysxManagerCfg(dt=dt, device=device, gravity=gravity) - sim_cfg = SimulationCfg(physics_manager_cfg=physics_manager_cfg) + physics_manager_cfg = PhysxManagerCfg(dt=dt, gravity=gravity) + sim_cfg = SimulationCfg(device=device, physics_manager_cfg=physics_manager_cfg) sim = SimulationContext(sim_cfg) diff --git a/source/isaaclab/test/sensors/test_sensor_base.py b/source/isaaclab/test/sensors/test_sensor_base.py index 244979caa29..e931d8a4e63 100644 --- a/source/isaaclab/test/sensors/test_sensor_base.py +++ b/source/isaaclab/test/sensors/test_sensor_base.py @@ -106,11 +106,8 @@ def create_dummy_sensor(request, device): yield sensor_cfg, sim, dt - # stop simulation - # note: cannot use self.sim.stop() since it does one render step after stopping!! This doesn't make sense :( - sim._timeline.stop() - # clear the stage - sim.clear_all_callbacks() + # stop simulation and clean up + sim.stop() sim.clear_instance() 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 ebe059bed66..80ad3a5a5bc 100644 --- a/source/isaaclab/test/sim/test_build_simulation_context_headless.py +++ b/source/isaaclab/test/sim/test_build_simulation_context_headless.py @@ -36,12 +36,12 @@ def test_build_simulation_context_no_cfg(gravity_enabled, device, dt): """Test that the simulation context is built when no simulation cfg is passed in.""" with build_simulation_context(gravity_enabled=gravity_enabled, device=device, dt=dt) as sim: if gravity_enabled: - assert sim.cfg.gravity == (0.0, 0.0, -9.81) + assert sim.cfg.physics_manager_cfg.gravity == (0.0, 0.0, -9.81) else: - assert sim.cfg.gravity == (0.0, 0.0, 0.0) + assert sim.cfg.physics_manager_cfg.gravity == (0.0, 0.0, 0.0) assert sim.cfg.device == device - assert sim.cfg.dt == dt + assert sim.cfg.physics_manager_cfg.dt == dt # Ensure that dome light didn't get added automatically as we are headless assert not sim.stage.GetPrimAtPath("/World/defaultDomeLight").IsValid() @@ -76,18 +76,23 @@ def test_build_simulation_context_auto_add_lighting(add_lighting, auto_add_light @pytest.mark.isaacsim_ci def test_build_simulation_context_cfg(): """Test that the simulation context is built with the correct cfg and values don't get overridden.""" + from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg + dt = 0.001 # Non-standard gravity gravity = (0.0, 0.0, -1.81) device = "cuda:0" cfg = SimulationCfg( - gravity=gravity, device=device, - dt=dt, + physics_manager_cfg=PhysxManagerCfg( + gravity=gravity, + dt=dt, + ), ) with build_simulation_context(sim_cfg=cfg, gravity_enabled=False, dt=0.01, device="cpu") as sim: - assert sim.cfg.gravity == gravity + # Values from sim_cfg should not be overridden by build_simulation_context args + assert sim.cfg.physics_manager_cfg.gravity == gravity assert sim.cfg.device == device - assert sim.cfg.dt == dt + assert sim.cfg.physics_manager_cfg.dt == dt diff --git a/source/isaaclab/test/sim/test_build_simulation_context_nonheadless.py b/source/isaaclab/test/sim/test_build_simulation_context_nonheadless.py index ae2203c43b7..57884a3a77c 100644 --- a/source/isaaclab/test/sim/test_build_simulation_context_nonheadless.py +++ b/source/isaaclab/test/sim/test_build_simulation_context_nonheadless.py @@ -34,12 +34,12 @@ def test_build_simulation_context_no_cfg(gravity_enabled, device, dt): """Test that the simulation context is built when no simulation cfg is passed in.""" with build_simulation_context(gravity_enabled=gravity_enabled, device=device, dt=dt) as sim: if gravity_enabled: - assert sim.cfg.gravity == (0.0, 0.0, -9.81) + assert sim.cfg.physics_manager_cfg.gravity == (0.0, 0.0, -9.81) else: - assert sim.cfg.gravity == (0.0, 0.0, 0.0) + assert sim.cfg.physics_manager_cfg.gravity == (0.0, 0.0, 0.0) assert sim.cfg.device == device - assert sim.cfg.dt == dt + assert sim.cfg.physics_manager_cfg.dt == dt @pytest.mark.parametrize("add_ground_plane", [True, False]) @@ -58,7 +58,10 @@ def test_build_simulation_context_ground_plane(add_ground_plane): def test_build_simulation_context_auto_add_lighting(add_lighting, auto_add_lighting): """Test that the simulation context is built with the correct lighting.""" with build_simulation_context(add_lighting=add_lighting, auto_add_lighting=auto_add_lighting) as sim: - if auto_add_lighting or add_lighting: + has_gui = sim.get_setting("/isaaclab/has_gui") + # Dome light is added if add_lighting=True OR (auto_add_lighting=True AND has_gui) + should_have_light = add_lighting or (auto_add_lighting and has_gui) + if should_have_light: # Ensure that dome light got added assert sim.stage.GetPrimAtPath("/World/defaultDomeLight").IsValid() else: @@ -68,18 +71,23 @@ def test_build_simulation_context_auto_add_lighting(add_lighting, auto_add_light def test_build_simulation_context_cfg(): """Test that the simulation context is built with the correct cfg and values don't get overridden.""" + from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg + dt = 0.001 # Non-standard gravity gravity = (0.0, 0.0, -1.81) device = "cuda:0" cfg = SimulationCfg( - gravity=gravity, device=device, - dt=dt, + physics_manager_cfg=PhysxManagerCfg( + gravity=gravity, + dt=dt, + ), ) with build_simulation_context(sim_cfg=cfg, gravity_enabled=False, dt=0.01, device="cpu") as sim: - assert sim.cfg.gravity == gravity + # Values from sim_cfg should not be overridden by build_simulation_context args + assert sim.cfg.physics_manager_cfg.gravity == gravity assert sim.cfg.device == device - assert sim.cfg.dt == dt + assert sim.cfg.physics_manager_cfg.dt == dt diff --git a/source/isaaclab/test/sim/test_simulation_context.py b/source/isaaclab/test/sim/test_simulation_context.py index 55d220cb418..e0a1f3b5297 100644 --- a/source/isaaclab/test/sim/test_simulation_context.py +++ b/source/isaaclab/test/sim/test_simulation_context.py @@ -12,95 +12,116 @@ """Rest everything follows.""" -from collections.abc import Generator - import numpy as np import pytest +import weakref -import omni.physx +import omni.timeline import isaaclab.sim as sim_utils -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sim import SimulationCfg, SimulationContext +from isaaclab_physx.physics import PhysxManager, PhysxManagerCfg, IsaacEvents @pytest.fixture(autouse=True) def test_setup_teardown(): """Setup and teardown for each test.""" - # Setup: Clear any existing simulation context + # Setup: Clear any existing simulation context and create a fresh stage SimulationContext.clear_instance() + sim_utils.create_new_stage() # Yield for the test yield - # Teardown: Clear the simulation context after each test SimulationContext.clear_instance() -@pytest.fixture -def sim_with_stage_in_memory() -> Generator[SimulationContext, None, None]: - """Create a simulation context with stage in memory.""" - # create stage in memory - cfg = SimulationCfg(create_stage_in_memory=True) - sim = SimulationContext(cfg=cfg) - # update stage - sim_utils.update_stage() - # yield simulation context - yield sim - # stop simulation - omni.physx.get_physx_simulation_interface().detach_stage() - sim.stop() - # clear simulation context - sim.clear() - sim.clear_all_callbacks() - sim.clear_instance() +""" +Basic Configuration Tests +""" @pytest.mark.isaacsim_ci -def test_singleton(): - """Tests that the singleton is working.""" - sim1 = SimulationContext() - sim2 = SimulationContext() - assert sim1 is sim2 - - # try to delete the singleton - sim2.clear_instance() - assert sim1.instance() is None - # create new instance - sim4 = SimulationContext() - assert sim1 is not sim4 - assert sim1.instance() is sim4.instance() +@pytest.mark.parametrize("device", ["cuda:0", "cpu"]) +def test_init(device): + """Test the simulation context initialization.""" + from isaaclab.sim.spawners.materials import RigidBodyMaterialCfg - -@pytest.mark.isaacsim_ci -def test_initialization(): - """Test the simulation config.""" - cfg = SimulationCfg(physics_prim_path="/Physics/PhysX", render_interval=5, gravity=(0.0, -0.5, -0.5)) - sim = SimulationContext(cfg) + physics_manager_cfg = PhysxManagerCfg( + physics_prim_path="/Physics/PhysX", + gravity=(0.0, -0.5, -0.5), + physics_material=RigidBodyMaterialCfg(), + ) + cfg = SimulationCfg(device=device, physics_manager_cfg=physics_manager_cfg, render_interval=5) + # sim = SimulationContext(cfg) # TODO: Figure out why keyword argument doesn't work. # note: added a fix in Isaac Sim 2023.1 for this. - # sim = SimulationContext(cfg=cfg) + sim = SimulationContext(cfg=cfg) + + # verify stage is valid + assert sim.stage is not None + # verify device property + assert sim.device == device + # verify no RTX sensors are available + assert not sim.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") + + # obtain physics scene from USD + from pxr import UsdPhysics + from pxr.PhysxSchema import PhysxSceneAPI + + physics_scene_prim = sim.stage.GetPrimAtPath("/Physics/PhysX") + assert physics_scene_prim.IsValid() + physics_scene = UsdPhysics.Scene(physics_scene_prim) + physx_scene_api = PhysxSceneAPI(physics_scene_prim) # check valid settings - assert sim.get_physics_dt() == cfg.dt - assert sim.get_rendering_dt() == cfg.dt * cfg.render_interval - assert not sim.has_rtx_sensors() + physics_hz = physx_scene_api.GetTimeStepsPerSecondAttr().Get() + physics_dt = 1.0 / physics_hz + assert physics_dt == cfg.physics_manager_cfg.dt + # check valid paths assert sim.stage.GetPrimAtPath("/Physics/PhysX").IsValid() assert sim.stage.GetPrimAtPath("/Physics/PhysX/defaultMaterial").IsValid() # check valid gravity - gravity_dir, gravity_mag = sim.get_physics_context().get_gravity() + gravity_dir, gravity_mag = ( + physics_scene.GetGravityDirectionAttr().Get(), + physics_scene.GetGravityMagnitudeAttr().Get(), + ) gravity = np.array(gravity_dir) * gravity_mag - np.testing.assert_almost_equal(gravity, cfg.gravity) + np.testing.assert_almost_equal(gravity, cfg.physics_manager_cfg.gravity) @pytest.mark.isaacsim_ci -def test_sim_version(): - """Test obtaining the version.""" - sim = SimulationContext() - version = sim.get_version() - assert len(version) > 0 - assert version[0] >= 4 +def test_instance_before_creation(): + """Test accessing instance before creating returns None.""" + # clear any existing instance + SimulationContext.clear_instance() + + # accessing instance before creation should return None + assert SimulationContext.instance() is None + + +@pytest.mark.isaacsim_ci +def test_singleton(): + """Tests that the singleton is working.""" + sim1 = SimulationContext() + sim2 = SimulationContext() + assert sim1 is sim2 + + # try to delete the singleton + sim2.clear_instance() + assert sim1.instance() is None + # create new instance + sim3 = SimulationContext() + assert sim1 is not sim3 + assert sim1.instance() is sim3.instance() + # clear instance + sim3.clear_instance() + + +""" +Property Tests. +""" @pytest.mark.isaacsim_ci @@ -111,8 +132,8 @@ def test_carb_setting(): sim.set_setting("/physics/physxDispatcher", False) assert sim.get_setting("/physics/physxDispatcher") is False # unknown carb setting - sim.set_setting("/myExt/using_omniverse_version", sim.get_version()) - assert tuple(sim.get_setting("/myExt/using_omniverse_version")) == tuple(sim.get_version()) + sim.set_setting("/myExt/test_value", 42) + assert sim.get_setting("/myExt/test_value") == 42 @pytest.mark.isaacsim_ci @@ -120,45 +141,917 @@ def test_headless_mode(): """Test that render mode is headless since we are running in headless mode.""" sim = SimulationContext() # check default render mode - assert sim.render_mode == sim.RenderMode.NO_GUI_OR_RENDERING + assert not sim.carb_settings.get("/isaaclab/has_gui") and not bool( + sim.carb_settings.get("/isaaclab/render/offscreen") + ) -# def test_boundedness(): -# """Test that the boundedness of the simulation context remains constant. -# -# Note: This test fails right now because Isaac Sim does not handle boundedness correctly. On creation, -# it is registering itself to various callbacks and hence the boundedness is more than 1. This may not be -# critical for the simulation context since we usually call various clear functions before deleting the -# simulation context. -# """ -# sim = SimulationContext() -# # manually set the boundedness to 1? -- this is not possible because of Isaac Sim. -# sim.clear_all_callbacks() -# sim._stage_open_callback = None -# sim._physics_timer_callback = None -# sim._event_timer_callback = None -# -# # check that boundedness of simulation context is correct -# sim_ref_count = ctypes.c_long.from_address(id(sim)).value -# # reset the simulation -# sim.reset() -# assert ctypes.c_long.from_address(id(sim)).value == sim_ref_count -# # step the simulation -# for _ in range(10): -# sim.step() -# assert ctypes.c_long.from_address(id(sim)).value == sim_ref_count -# # clear the simulation -# sim.clear_instance() -# assert ctypes.c_long.from_address(id(sim)).value == sim_ref_count - 1 +""" +Timeline Operations Tests. +""" + + +@pytest.mark.isaacsim_ci +def test_timeline_play_stop(): + """Test timeline play and stop operations.""" + sim = SimulationContext() + + # initially simulation should be stopped + assert sim.is_stopped() + assert not sim.is_playing() + + # start the simulation + sim.play() + assert sim.is_playing() + assert not sim.is_stopped() + + # disable callback to prevent app from continuing + sim._disable_app_control_on_stop_handle = True # type: ignore + # stop the simulation + sim.stop() + assert sim.is_stopped() + assert not sim.is_playing() @pytest.mark.isaacsim_ci -def test_zero_gravity(): - """Test that gravity can be properly disabled.""" - cfg = SimulationCfg(gravity=(0.0, 0.0, 0.0)) +def test_timeline_pause(): + """Test timeline pause operation.""" + sim = SimulationContext() + # start the simulation + sim.play() + assert sim.is_playing() + + # pause the simulation + sim.pause() + assert not sim.is_playing() + assert not sim.is_stopped() # paused is different from stopped + + +""" +Reset and Step Tests +""" + + +@pytest.mark.isaacsim_ci +def test_reset(): + """Test simulation reset.""" + cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01)) sim = SimulationContext(cfg) - gravity_dir, gravity_mag = sim.get_physics_context().get_gravity() - gravity = np.array(gravity_dir) * gravity_mag - np.testing.assert_almost_equal(gravity, cfg.gravity) + # create a simple cube to test with + cube_cfg = sim_utils.CuboidCfg(size=(0.1, 0.1, 0.1)) + cube_cfg.func("/World/Cube", cube_cfg) + + # reset the simulation + sim.reset() + + # check that simulation is playing after reset + assert sim.is_playing() + + # check that physics sim view is created + assert sim.physics_sim_view is not None + + +@pytest.mark.isaacsim_ci +def test_reset_soft(): + """Test soft reset (without stopping simulation).""" + cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01)) + sim = SimulationContext(cfg) + + # create a simple cube + cube_cfg = sim_utils.CuboidCfg(size=(0.1, 0.1, 0.1)) + cube_cfg.func("/World/Cube", cube_cfg) + + # perform initial reset + sim.reset() + assert sim.is_playing() + + # perform soft reset + sim.reset(soft=True) + + # simulation should still be playing + assert sim.is_playing() + + +@pytest.mark.isaacsim_ci +def test_forward(): + """Test forward propagation for fabric updates.""" + cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01, use_fabric=True)) + sim = SimulationContext(cfg) + + # create simple scene + cube_cfg = sim_utils.CuboidCfg(size=(0.1, 0.1, 0.1)) + cube_cfg.func("/World/Cube", cube_cfg) + + sim.reset() + + # call forward + sim.forward() + + # should not raise any errors + assert sim.is_playing() + + +@pytest.mark.isaacsim_ci +@pytest.mark.parametrize("render", [True, False]) +def test_step(render): + """Test stepping simulation with and without rendering.""" + cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01)) + sim = SimulationContext(cfg) + + # create simple scene + cube_cfg = sim_utils.CuboidCfg(size=(0.1, 0.1, 0.1)) + cube_cfg.func("/World/Cube", cube_cfg) + + sim.reset() + + # step with rendering + for _ in range(10): + sim.step(render=render) + + # simulation should still be playing + assert sim.is_playing() + + +@pytest.mark.isaacsim_ci +def test_render(): + """Test rendering simulation.""" + cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01)) + sim = SimulationContext(cfg) + + # create simple scene + cube_cfg = sim_utils.CuboidCfg(size=(0.1, 0.1, 0.1)) + cube_cfg.func("/World/Cube", cube_cfg) + + sim.reset() + + # render + for _ in range(10): + sim.render() + + # simulation should still be playing + assert sim.is_playing() + + +""" +Stage Operations Tests +""" + + +@pytest.mark.isaacsim_ci +def test_get_initial_stage(): + """Test getting the initial stage.""" + sim = SimulationContext() + + # get initial stage + stage = sim.stage + + # verify stage is valid + assert stage is not None + assert stage == sim.stage + + +@pytest.mark.isaacsim_ci +def test_clear_stage(): + """Test clearing the stage.""" + sim = SimulationContext() + + # create some objects + cube_cfg1 = sim_utils.CuboidCfg(size=(0.1, 0.1, 0.1)) + cube_cfg1.func("/World/Cube1", cube_cfg1) + cube_cfg2 = sim_utils.CuboidCfg(size=(0.1, 0.1, 0.1)) + cube_cfg2.func("/World/Cube2", cube_cfg2) + + # verify objects exist + assert sim.stage.GetPrimAtPath("/World/Cube1").IsValid() + assert sim.stage.GetPrimAtPath("/World/Cube2").IsValid() + + # clear the stage + sim.clear_stage() + + # verify objects are removed but World and Physics remain + assert not sim.stage.GetPrimAtPath("/World/Cube1").IsValid() + assert not sim.stage.GetPrimAtPath("/World/Cube2").IsValid() + assert sim.stage.GetPrimAtPath("/World").IsValid() + assert sim.stage.GetPrimAtPath(sim.cfg.physics_manager_cfg.physics_prim_path).IsValid() # type: ignore[union-attr] + + +""" +Physics Configuration Tests +""" + + +@pytest.mark.isaacsim_ci +@pytest.mark.parametrize("solver_type", [0, 1]) # 0=PGS, 1=TGS +def test_solver_type(solver_type): + """Test different solver types.""" + from pxr.PhysxSchema import PhysxSceneAPI + + cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(solver_type=solver_type)) + sim = SimulationContext(cfg) + + # obtain physics scene api from USD + physics_scene_prim = sim.stage.GetPrimAtPath(cfg.physics_manager_cfg.physics_prim_path) + physx_scene_api = PhysxSceneAPI(physics_scene_prim) + # check solver type is set + solver_type_str = "PGS" if solver_type == 0 else "TGS" + assert physx_scene_api.GetSolverTypeAttr().Get() == solver_type_str + + +@pytest.mark.isaacsim_ci +@pytest.mark.parametrize("use_fabric", [True, False]) +def test_fabric_setting(use_fabric): + """Test that fabric setting is properly set.""" + cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(use_fabric=use_fabric)) + sim = SimulationContext(cfg) + + # check fabric is enabled via physics setting + assert sim.carb_settings.get_as_bool("/isaaclab/fabric_enabled") == use_fabric + + +@pytest.mark.isaacsim_ci +@pytest.mark.parametrize("dt", [0.01, 0.02, 0.005]) +def test_physics_dt(dt): + """Test that physics time step is properly configured.""" + from pxr.PhysxSchema import PhysxSceneAPI + + cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=dt)) + sim = SimulationContext(cfg) + + # obtain physics scene api from USD + physics_scene_prim = sim.stage.GetPrimAtPath(cfg.physics_manager_cfg.physics_prim_path) + physx_scene_api = PhysxSceneAPI(physics_scene_prim) + # check physics dt + physics_hz = physx_scene_api.GetTimeStepsPerSecondAttr().Get() + physics_dt = 1.0 / physics_hz + assert abs(physics_dt - dt) < 1e-6 + + +@pytest.mark.isaacsim_ci +@pytest.mark.parametrize("gravity", [(0.0, 0.0, 0.0), (0.0, 0.0, -9.81), (0.5, 0.5, 0.5)]) +def test_custom_gravity(gravity): + """Test that gravity can be properly set.""" + from pxr import UsdPhysics + + cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(gravity=gravity)) + sim = SimulationContext(cfg) + + # obtain physics scene from USD + physics_scene_prim = sim.stage.GetPrimAtPath(cfg.physics_manager_cfg.physics_prim_path) + physics_scene = UsdPhysics.Scene(physics_scene_prim) + + gravity_dir, gravity_mag = ( + physics_scene.GetGravityDirectionAttr().Get(), + physics_scene.GetGravityMagnitudeAttr().Get(), + ) + actual_gravity = np.array(gravity_dir) * gravity_mag + np.testing.assert_almost_equal(actual_gravity, cfg.physics_manager_cfg.gravity, decimal=6) + + +""" +Callback Tests. +""" + + +@pytest.mark.isaacsim_ci +def test_timeline_callbacks_on_play(): + """Test that timeline callbacks are triggered on play event.""" + cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01)) + sim = SimulationContext(cfg) + + # create a simple scene + cube_cfg = sim_utils.CuboidCfg(size=(0.1, 0.1, 0.1)) + cube_cfg.func("/World/Cube", cube_cfg) + + # create a flag to track callback execution + callback_state = {"play_called": False, "stop_called": False} + + # define callback functions + def on_play_callback(event): + callback_state["play_called"] = True + + def on_stop_callback(event): + callback_state["stop_called"] = True + + # register callbacks + timeline_event_stream = omni.timeline.get_timeline_interface().get_timeline_event_stream() + play_handle = timeline_event_stream.create_subscription_to_pop_by_type( + int(omni.timeline.TimelineEventType.PLAY), + lambda event: on_play_callback(event), + order=20, + ) + stop_handle = timeline_event_stream.create_subscription_to_pop_by_type( + int(omni.timeline.TimelineEventType.STOP), + lambda event: on_stop_callback(event), + order=20, + ) + + try: + # ensure callbacks haven't been called yet + assert not callback_state["play_called"] + assert not callback_state["stop_called"] + + # play the simulation - this should trigger play callback + sim.play() + assert callback_state["play_called"] + assert not callback_state["stop_called"] + + # reset flags + callback_state["play_called"] = False + + # disable app control to prevent hanging + sim._disable_app_control_on_stop_handle = True # type: ignore + + # stop the simulation - this should trigger stop callback + sim.stop() + assert callback_state["stop_called"] + + finally: + # cleanup callbacks + if play_handle is not None: + play_handle.unsubscribe() + if stop_handle is not None: + stop_handle.unsubscribe() + + +@pytest.mark.isaacsim_ci +def test_timeline_callbacks_with_weakref(): + """Test that timeline callbacks work correctly with weak references (similar to asset_base.py).""" + + cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01)) + sim = SimulationContext(cfg) + + # create a simple scene + cube_cfg = sim_utils.CuboidCfg(size=(0.1, 0.1, 0.1)) + cube_cfg.func("/World/Cube", cube_cfg) + + # create a test object that will be weakly referenced + class CallbackTracker: + def __init__(self): + self.play_count = 0 + self.stop_count = 0 + + def on_play(self, event): + self.play_count += 1 + + def on_stop(self, event): + self.stop_count += 1 + + # create an instance of the callback tracker + tracker = CallbackTracker() + + # define safe callback wrapper (similar to asset_base.py pattern) + def safe_callback(callback_name, event, obj_ref): + """Safely invoke a callback on a weakly-referenced object.""" + try: + obj = obj_ref() # Dereference the weakref + if obj is not None: + getattr(obj, callback_name)(event) + except ReferenceError: + # Object has been deleted; ignore + pass + + # register callbacks with weakref + obj_ref = weakref.ref(tracker) + timeline_event_stream = omni.timeline.get_timeline_interface().get_timeline_event_stream() + + play_handle = timeline_event_stream.create_subscription_to_pop_by_type( + int(omni.timeline.TimelineEventType.PLAY), + lambda event, obj_ref=obj_ref: safe_callback("on_play", event, obj_ref), + order=20, + ) + stop_handle = timeline_event_stream.create_subscription_to_pop_by_type( + int(omni.timeline.TimelineEventType.STOP), + lambda event, obj_ref=obj_ref: safe_callback("on_stop", event, obj_ref), + order=20, + ) + + try: + # verify callbacks haven't been called + assert tracker.play_count == 0 + assert tracker.stop_count == 0 + + # trigger play event + sim.play() + assert tracker.play_count == 1 + assert tracker.stop_count == 0 + + # disable app control to prevent hanging + sim._disable_app_control_on_stop_handle = True # type: ignore + + # trigger stop event + sim.stop() + assert tracker.play_count == 1 + assert tracker.stop_count == 1 + + # delete the tracker object + del tracker + + # trigger events again - callbacks should handle the deleted object gracefully + sim.play() + # disable app control again + sim._disable_app_control_on_stop_handle = True # type: ignore + sim.stop() + # should not raise any errors + + finally: + # cleanup callbacks + if play_handle is not None: + play_handle.unsubscribe() + if stop_handle is not None: + stop_handle.unsubscribe() + + +@pytest.mark.isaacsim_ci +def test_multiple_callbacks_on_same_event(): + """Test that multiple callbacks can be registered for the same event.""" + cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01)) + sim = SimulationContext(cfg) + + # create tracking for multiple callbacks + callback_counts = {"callback1": 0, "callback2": 0, "callback3": 0} + + def callback1(event): + callback_counts["callback1"] += 1 + + def callback2(event): + callback_counts["callback2"] += 1 + + def callback3(event): + callback_counts["callback3"] += 1 + + # register multiple callbacks for play event + timeline_event_stream = omni.timeline.get_timeline_interface().get_timeline_event_stream() + handle1 = timeline_event_stream.create_subscription_to_pop_by_type( + int(omni.timeline.TimelineEventType.PLAY), lambda event: callback1(event), order=20 + ) + handle2 = timeline_event_stream.create_subscription_to_pop_by_type( + int(omni.timeline.TimelineEventType.PLAY), lambda event: callback2(event), order=21 + ) + handle3 = timeline_event_stream.create_subscription_to_pop_by_type( + int(omni.timeline.TimelineEventType.PLAY), lambda event: callback3(event), order=22 + ) + + try: + # verify none have been called + assert all(count == 0 for count in callback_counts.values()) + + # trigger play event + sim.play() + + # all callbacks should have been called + assert callback_counts["callback1"] == 1 + assert callback_counts["callback2"] == 1 + assert callback_counts["callback3"] == 1 + + finally: + # cleanup all callbacks + if handle1 is not None: + handle1.unsubscribe() + if handle2 is not None: + handle2.unsubscribe() + if handle3 is not None: + handle3.unsubscribe() + + +@pytest.mark.isaacsim_ci +def test_callback_execution_order(): + """Test that callbacks are executed in the correct order based on priority.""" + cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01)) + sim = SimulationContext(cfg) + + # track execution order + execution_order = [] + + def callback_low_priority(event): + execution_order.append("low") + + def callback_medium_priority(event): + execution_order.append("medium") + + def callback_high_priority(event): + execution_order.append("high") + + # register callbacks with different priorities (lower order = higher priority) + timeline_event_stream = omni.timeline.get_timeline_interface().get_timeline_event_stream() + handle_high = timeline_event_stream.create_subscription_to_pop_by_type( + int(omni.timeline.TimelineEventType.PLAY), lambda event: callback_high_priority(event), order=5 + ) + handle_medium = timeline_event_stream.create_subscription_to_pop_by_type( + int(omni.timeline.TimelineEventType.PLAY), lambda event: callback_medium_priority(event), order=10 + ) + handle_low = timeline_event_stream.create_subscription_to_pop_by_type( + int(omni.timeline.TimelineEventType.PLAY), lambda event: callback_low_priority(event), order=15 + ) + + try: + # trigger play event + sim.play() + + # verify callbacks were executed in correct order + assert len(execution_order) == 3 + assert execution_order[0] == "high" + assert execution_order[1] == "medium" + assert execution_order[2] == "low" + + finally: + # cleanup callbacks + if handle_high is not None: + handle_high.unsubscribe() + if handle_medium is not None: + handle_medium.unsubscribe() + if handle_low is not None: + handle_low.unsubscribe() + + +@pytest.mark.isaacsim_ci +def test_callback_unsubscribe(): + """Test that unsubscribing callbacks works correctly.""" + cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01)) + sim = SimulationContext(cfg) + + # create callback counter + callback_count = {"count": 0} + + def on_play_callback(event): + callback_count["count"] += 1 + + # register callback + timeline_event_stream = omni.timeline.get_timeline_interface().get_timeline_event_stream() + play_handle = timeline_event_stream.create_subscription_to_pop_by_type( + int(omni.timeline.TimelineEventType.PLAY), lambda event: on_play_callback(event), order=20 + ) + + try: + # trigger play event + sim.play() + assert callback_count["count"] == 1 + + # stop simulation + sim._disable_app_control_on_stop_handle = True # type: ignore + sim.stop() + + # unsubscribe the callback + play_handle.unsubscribe() + play_handle = None + + # trigger play event again + sim.play() + + # callback should not have been called again (still 1) + assert callback_count["count"] == 1 + + finally: + # cleanup if needed + if play_handle is not None: + play_handle.unsubscribe() + + +@pytest.mark.isaacsim_ci +def test_pause_event_callback(): + """Test that pause event callbacks are triggered correctly.""" + cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01)) + sim = SimulationContext(cfg) + + # create callback tracker + callback_state = {"pause_called": False} + + def on_pause_callback(event): + callback_state["pause_called"] = True + + # register pause callback + timeline_event_stream = omni.timeline.get_timeline_interface().get_timeline_event_stream() + pause_handle = timeline_event_stream.create_subscription_to_pop_by_type( + int(omni.timeline.TimelineEventType.PAUSE), lambda event: on_pause_callback(event), order=20 + ) + + try: + # play the simulation first + sim.play() + assert not callback_state["pause_called"] + + # pause the simulation + sim.pause() + + # callback should have been triggered + assert callback_state["pause_called"] + + finally: + # cleanup + if pause_handle is not None: + pause_handle.unsubscribe() + + +""" +Isaac Events Callback Tests. +""" + + +@pytest.mark.isaacsim_ci +@pytest.mark.parametrize( + "event_type", + [IsaacEvents.PHYSICS_WARMUP, IsaacEvents.SIMULATION_VIEW_CREATED, IsaacEvents.PHYSICS_READY], +) +def test_isaac_event_triggered_on_reset(event_type): + """Test that Isaac events are triggered during reset.""" + cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01)) + sim = SimulationContext(cfg) + + # create simple scene + cube_cfg = sim_utils.CuboidCfg(size=(0.1, 0.1, 0.1)) + cube_cfg.func("/World/Cube", cube_cfg) + + # create callback tracker + callback_state = {"called": False} + + def on_event(event): + callback_state["called"] = True + + # register callback for the event + callback_id = PhysxManager.register_callback(lambda event: on_event(event), event=event_type) + + try: + # verify callback hasn't been called yet + assert not callback_state["called"] + + # reset the simulation - should trigger the event + sim.reset() + + # verify callback was triggered + assert callback_state["called"] + + finally: + # cleanup callback + if callback_id is not None: + PhysxManager.deregister_callback(callback_id) + + +@pytest.mark.isaacsim_ci +def test_isaac_event_prim_deletion(): + """Test that PRIM_DELETION Isaac event is triggered when a prim is deleted.""" + cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01)) + sim = SimulationContext(cfg) + + # create simple scene + cube_cfg = sim_utils.CuboidCfg(size=(0.1, 0.1, 0.1)) + cube_cfg.func("/World/Cube", cube_cfg) + + sim.reset() + + # create callback tracker + callback_state = {"prim_deleted": False, "deleted_path": None} + + def on_prim_deletion(event): + callback_state["prim_deleted"] = True + # event payload should contain the deleted prim path + if hasattr(event, "payload") and event.payload: + callback_state["deleted_path"] = event.payload.get("prim_path") + + # register callback for PRIM_DELETION event + callback_id = PhysxManager.register_callback( + lambda event: on_prim_deletion(event), event=IsaacEvents.PRIM_DELETION + ) + + try: + # verify callback hasn't been called yet + assert not callback_state["prim_deleted"] + + # delete the cube prim + sim_utils.delete_prim("/World/Cube") + + # trigger the event by dispatching it manually (since deletion might be handled differently) + PhysxManager._message_bus.dispatch_event(IsaacEvents.PRIM_DELETION.value, payload={"prim_path": "/World/Cube"}) # type: ignore + + # verify callback was triggered + assert callback_state["prim_deleted"] + + finally: + # cleanup callback + if callback_id is not None: + PhysxManager.deregister_callback(callback_id) + + +@pytest.mark.isaacsim_ci +def test_isaac_event_timeline_stop(): + """Test that TIMELINE_STOP Isaac event can be registered and triggered.""" + cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01)) + sim = SimulationContext(cfg) + + # create callback tracker + callback_state = {"timeline_stop_called": False} + + def on_timeline_stop(event): + callback_state["timeline_stop_called"] = True + + # register callback for TIMELINE_STOP event + callback_id = PhysxManager.register_callback( + lambda event: on_timeline_stop(event), event=IsaacEvents.TIMELINE_STOP + ) + + try: + # verify callback hasn't been called yet + assert not callback_state["timeline_stop_called"] + + # play and stop the simulation + sim.play() + + # disable app control to prevent hanging + sim._disable_app_control_on_stop_handle = True # type: ignore + + # stop the simulation + sim.stop() + + # dispatch the event manually + PhysxManager._message_bus.dispatch_event(IsaacEvents.TIMELINE_STOP.value, payload={}) # type: ignore + + # verify callback was triggered + assert callback_state["timeline_stop_called"] + + finally: + # cleanup callback + if callback_id is not None: + PhysxManager.deregister_callback(callback_id) + + +@pytest.mark.isaacsim_ci +def test_isaac_event_callbacks_with_weakref(): + """Test Isaac event callbacks with weak references (similar to asset_base.py pattern).""" + cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01)) + sim = SimulationContext(cfg) + + # create simple scene + cube_cfg = sim_utils.CuboidCfg(size=(0.1, 0.1, 0.1)) + cube_cfg.func("/World/Cube", cube_cfg) + + # create a test object that will be weakly referenced + class PhysicsTracker: + def __init__(self): + self.warmup_count = 0 + self.ready_count = 0 + + def on_warmup(self, event): + self.warmup_count += 1 + + def on_ready(self, event): + self.ready_count += 1 + + tracker = PhysicsTracker() + + # define safe callback wrapper (same pattern as asset_base.py) + def safe_callback(callback_name, event, obj_ref): + """Safely invoke a callback on a weakly-referenced object.""" + try: + obj = obj_ref() + if obj is not None: + getattr(obj, callback_name)(event) + except ReferenceError: + # Object has been deleted; ignore + pass + + # register callbacks with weakref + obj_ref = weakref.ref(tracker) + + warmup_id = PhysxManager.register_callback( + lambda event, obj_ref=obj_ref: safe_callback("on_warmup", event, obj_ref), + event=IsaacEvents.PHYSICS_WARMUP, + ) + ready_id = PhysxManager.register_callback( + lambda event, obj_ref=obj_ref: safe_callback("on_ready", event, obj_ref), event=IsaacEvents.PHYSICS_READY + ) + + try: + # verify callbacks haven't been called + assert tracker.warmup_count == 0 + assert tracker.ready_count == 0 + + # reset simulation - triggers WARMUP and READY events + sim.reset() + + # verify callbacks were triggered (may be called multiple times during warmup sequence) + assert tracker.warmup_count >= 1 + assert tracker.ready_count >= 1 + + # delete the tracker object + del tracker + + # reset again - callbacks should handle the deleted object gracefully + sim.reset(soft=True) + + # should not raise any errors even though tracker is deleted + + finally: + # cleanup callbacks + if warmup_id is not None: + PhysxManager.deregister_callback(warmup_id) + if ready_id is not None: + PhysxManager.deregister_callback(ready_id) + + +@pytest.mark.isaacsim_ci +def test_multiple_isaac_event_callbacks(): + """Test that multiple callbacks can be registered for the same Isaac event.""" + cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01)) + sim = SimulationContext(cfg) + + # create simple scene + cube_cfg = sim_utils.CuboidCfg(size=(0.1, 0.1, 0.1)) + cube_cfg.func("/World/Cube", cube_cfg) + + # create tracking for multiple callbacks + callback_counts = {"callback1": 0, "callback2": 0, "callback3": 0} + + def callback1(event): + callback_counts["callback1"] += 1 + + def callback2(event): + callback_counts["callback2"] += 1 + + def callback3(event): + callback_counts["callback3"] += 1 + + # register multiple callbacks for PHYSICS_READY event + id1 = PhysxManager.register_callback(lambda event: callback1(event), event=IsaacEvents.PHYSICS_READY) + id2 = PhysxManager.register_callback(lambda event: callback2(event), event=IsaacEvents.PHYSICS_READY) + id3 = PhysxManager.register_callback(lambda event: callback3(event), event=IsaacEvents.PHYSICS_READY) + + try: + # verify none have been called + assert all(count == 0 for count in callback_counts.values()) + + # reset simulation - triggers PHYSICS_READY event + sim.reset() + + # all callbacks should have been called (may be called multiple times during warmup sequence) + assert callback_counts["callback1"] >= 1 + assert callback_counts["callback2"] >= 1 + assert callback_counts["callback3"] >= 1 + + finally: + # cleanup all callbacks + if id1 is not None: + PhysxManager.deregister_callback(id1) + if id2 is not None: + PhysxManager.deregister_callback(id2) + if id3 is not None: + PhysxManager.deregister_callback(id3) + + +""" +Exception Handling in Callbacks Tests. +""" + + +@pytest.mark.isaacsim_ci +def test_exception_in_callback_on_reset(): + """Test that exceptions stored during reset are raised.""" + cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01)) + sim = SimulationContext(cfg) + + # create simple scene + cube_cfg = sim_utils.CuboidCfg(size=(0.1, 0.1, 0.1)) + cube_cfg.func("/World/Cube", cube_cfg) + + test_error_message = "Test exception on reset" + + def failing_callback(event): + PhysxManager.store_callback_exception(RuntimeError(test_error_message)) + + handle = PhysxManager.register_callback(failing_callback, event=IsaacEvents.PHYSICS_READY) + + try: + with pytest.raises(RuntimeError, match=test_error_message): + sim.reset() + finally: + if handle is not None: + PhysxManager.deregister_callback(handle) + SimulationContext.clear_instance() + + +@pytest.mark.isaacsim_ci +def test_exception_in_callback_on_step(): + """Test that exceptions stored during step are raised.""" + cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01)) + sim = SimulationContext(cfg) + + # create simple scene + cube_cfg = sim_utils.CuboidCfg(size=(0.1, 0.1, 0.1)) + cube_cfg.func("/World/Cube", cube_cfg) + + # reset first to initialize + sim.reset() + + test_error_message = "Test exception on step" + + def failing_callback(event): + PhysxManager.store_callback_exception(RuntimeError(test_error_message)) + + handle = PhysxManager.register_callback(failing_callback, event=IsaacEvents.POST_PHYSICS_STEP) + + try: + with pytest.raises(RuntimeError, match=test_error_message): + sim.step() + finally: + if handle is not None: + PhysxManager.deregister_callback(handle) + SimulationContext.clear_instance() diff --git a/source/isaaclab_physx/isaaclab_physx/__init__.py b/source/isaaclab_physx/isaaclab_physx/__init__.py index 68a8a553287..a9f5f5bf9d9 100644 --- a/source/isaaclab_physx/isaaclab_physx/__init__.py +++ b/source/isaaclab_physx/isaaclab_physx/__init__.py @@ -6,6 +6,7 @@ """Package containing the PhysX simulation interfaces for IsaacLab core package.""" import os +import sys import toml # Conveniences to other module directories via relative paths @@ -17,3 +18,20 @@ # Configure the module-level variables __version__ = ISAACLAB_PHYSX_METADATA["package"]["version"] + + +def _patch_isaacsim_simulation_manager(): + """Patch Isaac Sim's SimulationManager to use PhysxManager. + + This ensures all code that imports from isaacsim.core.simulation_manager + will use our PhysxManager instead, preventing duplicate callback registration. + """ + if "isaacsim.core.simulation_manager" in sys.modules: + original_module = sys.modules["isaacsim.core.simulation_manager"] + from .physics.physx_manager import PhysxManager, IsaacEvents + + original_module.SimulationManager = PhysxManager + original_module.IsaacEvents = IsaacEvents + + +_patch_isaacsim_simulation_manager() From 5efc9a12c982b6e45e691167be3b86434572b31f Mon Sep 17 00:00:00 2001 From: Octi Zhang Date: Fri, 6 Feb 2026 17:39:40 -0800 Subject: [PATCH 04/46] fix bug --- .../isaaclab_physx/physics/physx_manager.py | 17 ++++++++++------- 1 file changed, 10 insertions(+), 7 deletions(-) diff --git a/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py b/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py index 4e566f579f0..3b8fec86e70 100644 --- a/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py +++ b/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py @@ -196,6 +196,7 @@ def initialize(cls, sim_context: "SimulationContext") -> None: super().initialize(sim_context) cls._stage_id = get_current_stage_id() + cls._setup_subscriptions() cls._configure_physics() cls._load_fabric() @@ -484,6 +485,13 @@ def _warmup_and_create_views(cls) -> None: if not cls._warmup_needed: return + # Get stage ID first (needed for both warmup and view creation) + from isaaclab.sim.utils.stage import get_current_stage_id + stage_id = get_current_stage_id() + + # Attach stage to PhysX BEFORE loading/starting - critical for GPU pipeline + cls._physx_sim.attach_stage(stage_id) + # warmup physx cls._physx.force_load_physics_from_usd() cls._physx.start_simulation() @@ -495,13 +503,7 @@ def _warmup_and_create_views(cls) -> None: if cls._view_created: return - # create tensor views - from isaaclab.sim.utils.stage import get_current_stage_id - stage_id = get_current_stage_id() - - # attach stage to PhysX before creating views - cls._physx_sim.attach_stage(stage_id) - + # Create tensor views cls._view = omni.physics.tensors.create_simulation_view("torch", stage_id=stage_id) cls._view_warp = omni.physics.tensors.create_simulation_view("warp", stage_id=stage_id) @@ -510,6 +512,7 @@ def _warmup_and_create_views(cls) -> None: if cls._view_warp: cls._view_warp.set_subspace_roots("/") + # Final update after view creation cls._physx.update_simulation(cls.get_physics_dt(), 0.0) cls._view_created = True From 7ab8c210fc69107add550fe4512e8efa8b0cf3d4 Mon Sep 17 00:00:00 2001 From: Octi Zhang Date: Fri, 6 Feb 2026 18:18:05 -0800 Subject: [PATCH 05/46] pass precommit --- .../benchmarks/benchmark_view_comparison.py | 6 +- scripts/demos/bin_packing.py | 2 +- scripts/demos/bipeds.py | 2 +- scripts/demos/deformables.py | 2 +- scripts/demos/hands.py | 2 +- scripts/demos/markers.py | 2 +- scripts/demos/multi_asset.py | 3 +- scripts/demos/procedural_terrain.py | 2 +- scripts/demos/quadcopter.py | 2 +- scripts/demos/quadrupeds.py | 2 +- scripts/demos/sensors/cameras.py | 6 +- scripts/demos/sensors/contact_sensor.py | 2 +- .../demos/sensors/frame_transformer_sensor.py | 2 +- scripts/demos/sensors/imu_sensor.py | 2 +- scripts/demos/sensors/multi_mesh_raycaster.py | 2 +- .../sensors/multi_mesh_raycaster_camera.py | 2 +- scripts/demos/sensors/raycaster_sensor.py | 2 +- scripts/tools/check_instanceable.py | 3 +- scripts/tutorials/00_sim/create_empty.py | 1 + scripts/tutorials/00_sim/launch_app.py | 3 +- scripts/tutorials/00_sim/log_time.py | 1 + scripts/tutorials/00_sim/spawn_prims.py | 3 +- .../04_sensors/add_sensors_on_robot.py | 2 +- .../04_sensors/run_frame_transformer.py | 2 +- .../tutorials/04_sensors/run_usd_camera.py | 6 +- .../tutorials/05_controllers/run_diff_ik.py | 2 +- scripts/tutorials/05_controllers/run_osc.py | 2 +- source/isaaclab/isaaclab/assets/asset_base.py | 2 +- .../isaaclab/isaaclab/envs/direct_marl_env.py | 8 ++- .../isaaclab/isaaclab/envs/direct_rl_env.py | 13 +++- .../isaaclab/envs/manager_based_env.py | 4 +- .../isaaclab/envs/manager_based_rl_env.py | 13 +++- .../isaaclab/envs/ui/base_env_window.py | 4 +- .../isaaclab/physics/physics_manager.py | 20 ++---- .../isaaclab/physics/physics_manager_cfg.py | 5 +- .../isaaclab/sensors/ray_caster/ray_caster.py | 2 +- .../isaaclab/isaaclab/sensors/sensor_base.py | 4 +- .../isaaclab/isaaclab/sim/simulation_cfg.py | 29 ++++---- .../isaaclab/sim/simulation_context.py | 8 ++- .../test/app/test_non_headless_launch.py | 3 +- .../test/assets/check_external_force.py | 2 +- .../test/assets/check_fixed_base_assets.py | 2 +- .../test/controllers/test_differential_ik.py | 2 +- .../controllers/test_operational_space.py | 2 +- .../isaaclab/test/devices/check_keyboard.py | 3 +- .../test/envs/test_env_rendering_logic.py | 14 ++-- .../test/managers/test_observation_manager.py | 2 +- .../test/markers/check_markers_visibility.py | 3 +- .../markers/test_visualization_markers.py | 2 +- .../test/scene/check_interactive_scene.py | 3 +- source/isaaclab/test/sensors/test_camera.py | 2 +- .../test_multi_mesh_ray_caster_camera.py | 2 +- .../test/sensors/test_multi_tiled_camera.py | 2 +- .../test/sensors/test_ray_caster_camera.py | 2 +- .../isaaclab/test/sensors/test_sensor_base.py | 2 +- .../test/sensors/test_tiled_camera.py | 2 +- source/isaaclab/test/sim/check_meshes.py | 2 +- .../isaaclab/test/sim/test_mesh_converter.py | 2 +- .../isaaclab/test/sim/test_mjcf_converter.py | 2 +- source/isaaclab/test/sim/test_schemas.py | 2 +- .../test/sim/test_simulation_context.py | 13 ++-- .../test/sim/test_spawn_from_files.py | 2 +- source/isaaclab/test/sim/test_spawn_lights.py | 2 +- .../isaaclab/test/sim/test_spawn_materials.py | 2 +- source/isaaclab/test/sim/test_spawn_meshes.py | 2 +- .../isaaclab/test/sim/test_spawn_sensors.py | 2 +- source/isaaclab/test/sim/test_spawn_shapes.py | 2 +- .../isaaclab/test/sim/test_spawn_wrappers.py | 2 +- .../isaaclab/test/sim/test_urdf_converter.py | 2 +- .../test/sim/test_views_xform_prim.py | 7 +- .../check_scene_xr_visualization.py | 3 +- .../test/sensors/test_visuotactile_sensor.py | 2 +- .../assets/articulation/articulation.py | 3 +- .../assets/articulation/articulation_data.py | 4 +- .../deformable_object/deformable_object.py | 3 +- .../assets/rigid_object/rigid_object.py | 3 +- .../assets/rigid_object/rigid_object_data.py | 4 +- .../rigid_object_collection.py | 3 +- .../rigid_object_collection_data.py | 4 +- .../isaaclab_physx/physics/physx_manager.py | 67 ++++++++++++++----- .../physics/physx_manager_cfg.py | 12 ++-- .../sensors/contact_sensor/contact_sensor.py | 3 +- .../frame_transformer/frame_transformer.py | 3 +- .../isaaclab_physx/sensors/imu/imu.py | 3 +- .../isaaclab_physx/visualizers/__init__.py | 5 ++ .../visualizers/physx_ov_visualizer.py | 24 ++++--- .../visualizers/physx_ov_visualizer_cfg.py | 2 +- .../test/sensors/check_contact_sensor.py | 2 +- .../test/sensors/test_contact_sensor.py | 2 +- .../test/sensors/test_frame_transformer.py | 6 +- .../isaaclab_physx/test/sensors/test_imu.py | 6 +- .../allegro_hand/allegro_hand_env_cfg.py | 3 +- .../isaaclab_tasks/direct/ant/ant_env.py | 3 +- .../cart_double_pendulum_env.py | 2 +- .../direct/cartpole/cartpole_camera_env.py | 2 +- .../direct/cartpole/cartpole_env.py | 2 +- .../direct/humanoid/humanoid_env.py | 3 +- 97 files changed, 276 insertions(+), 177 deletions(-) diff --git a/scripts/benchmarks/benchmark_view_comparison.py b/scripts/benchmarks/benchmark_view_comparison.py index 9302545285f..a4029371c4a 100644 --- a/scripts/benchmarks/benchmark_view_comparison.py +++ b/scripts/benchmarks/benchmark_view_comparison.py @@ -69,11 +69,11 @@ import time import torch +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaacsim.core.simulation_manager import SimulationManager import isaaclab.sim as sim_utils -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sim.views import XformPrimView @@ -99,7 +99,9 @@ def benchmark_view(view_type: str, num_iterations: int) -> tuple[dict[str, float sim_utils.create_new_stage() # Create simulation context start_time = time.perf_counter() - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics_manager_cfg=PhysxManagerCfg(dt=0.01, use_fabric=(view_type == "xform_fabric"))) + sim_cfg = sim_utils.SimulationCfg( + device=args_cli.device, physics_manager_cfg=PhysxManagerCfg(dt=0.01, use_fabric=(view_type == "xform_fabric")) + ) sim = sim_utils.SimulationContext(sim_cfg) stage = sim_utils.get_current_stage() diff --git a/scripts/demos/bin_packing.py b/scripts/demos/bin_packing.py index d72faa0dd7a..732d08b73c4 100644 --- a/scripts/demos/bin_packing.py +++ b/scripts/demos/bin_packing.py @@ -44,9 +44,9 @@ import math import torch +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg import isaaclab.sim as sim_utils -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg import isaaclab.utils.math as math_utils from isaaclab.assets import AssetBaseCfg, RigidObjectCfg, RigidObjectCollection, RigidObjectCollectionCfg from isaaclab.scene import InteractiveScene, InteractiveSceneCfg diff --git a/scripts/demos/bipeds.py b/scripts/demos/bipeds.py index 2995d5ffc6c..ac34dd28f5e 100644 --- a/scripts/demos/bipeds.py +++ b/scripts/demos/bipeds.py @@ -33,9 +33,9 @@ """Rest everything follows.""" import torch +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg import isaaclab.sim as sim_utils -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.assets import Articulation from isaaclab.sim import SimulationContext diff --git a/scripts/demos/deformables.py b/scripts/demos/deformables.py index 3a99c4116c6..41c92dc8465 100644 --- a/scripts/demos/deformables.py +++ b/scripts/demos/deformables.py @@ -36,9 +36,9 @@ import numpy as np import torch import tqdm +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg import isaaclab.sim as sim_utils -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.assets import DeformableObject, DeformableObjectCfg diff --git a/scripts/demos/hands.py b/scripts/demos/hands.py index c70a7258911..1012e4b5680 100644 --- a/scripts/demos/hands.py +++ b/scripts/demos/hands.py @@ -34,9 +34,9 @@ import numpy as np import torch +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg import isaaclab.sim as sim_utils -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.assets import Articulation ## diff --git a/scripts/demos/markers.py b/scripts/demos/markers.py index f700a12ad0f..ca99bde625e 100644 --- a/scripts/demos/markers.py +++ b/scripts/demos/markers.py @@ -32,9 +32,9 @@ """Rest everything follows.""" import torch +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg import isaaclab.sim as sim_utils -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.markers import VisualizationMarkers, VisualizationMarkersCfg from isaaclab.sim import SimulationContext from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR, ISAACLAB_NUCLEUS_DIR diff --git a/scripts/demos/multi_asset.py b/scripts/demos/multi_asset.py index a8551687473..6834ef015c0 100644 --- a/scripts/demos/multi_asset.py +++ b/scripts/demos/multi_asset.py @@ -37,10 +37,11 @@ import random +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg + from pxr import Gf, Sdf import isaaclab.sim as sim_utils -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.assets import ( Articulation, ArticulationCfg, diff --git a/scripts/demos/procedural_terrain.py b/scripts/demos/procedural_terrain.py index 4885f3a76c9..4f7fc456f56 100644 --- a/scripts/demos/procedural_terrain.py +++ b/scripts/demos/procedural_terrain.py @@ -68,9 +68,9 @@ import random import torch +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg import isaaclab.sim as sim_utils -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.assets import AssetBase from isaaclab.markers import VisualizationMarkers, VisualizationMarkersCfg from isaaclab.terrains import FlatPatchSamplingCfg, TerrainImporter, TerrainImporterCfg diff --git a/scripts/demos/quadcopter.py b/scripts/demos/quadcopter.py index 10b83bf3415..05aec2aaba1 100644 --- a/scripts/demos/quadcopter.py +++ b/scripts/demos/quadcopter.py @@ -33,9 +33,9 @@ """Rest everything follows.""" import torch +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg import isaaclab.sim as sim_utils -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.assets import Articulation from isaaclab.sim import SimulationContext diff --git a/scripts/demos/quadrupeds.py b/scripts/demos/quadrupeds.py index 091844ba27d..d970b2413ba 100644 --- a/scripts/demos/quadrupeds.py +++ b/scripts/demos/quadrupeds.py @@ -34,9 +34,9 @@ import numpy as np import torch +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg import isaaclab.sim as sim_utils -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.assets import Articulation ## diff --git a/scripts/demos/sensors/cameras.py b/scripts/demos/sensors/cameras.py index 6caa2a92b9b..f107c73d49e 100644 --- a/scripts/demos/sensors/cameras.py +++ b/scripts/demos/sensors/cameras.py @@ -42,9 +42,9 @@ import matplotlib.pyplot as plt import numpy as np import torch +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg import isaaclab.sim as sim_utils -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.assets import ArticulationCfg, AssetBaseCfg from isaaclab.scene import InteractiveScene, InteractiveSceneCfg from isaaclab.sensors import CameraCfg, RayCasterCameraCfg, TiledCameraCfg @@ -281,7 +281,9 @@ def run_simulator(sim: sim_utils.SimulationContext, scene: InteractiveScene): def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics_manager_cfg=PhysxManagerCfg(dt=0.005, use_fabric=not args_cli.disable_fabric)) + sim_cfg = sim_utils.SimulationCfg( + device=args_cli.device, physics_manager_cfg=PhysxManagerCfg(dt=0.005, use_fabric=not args_cli.disable_fabric) + ) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) diff --git a/scripts/demos/sensors/contact_sensor.py b/scripts/demos/sensors/contact_sensor.py index bea383c7739..5a09d5f5fb6 100644 --- a/scripts/demos/sensors/contact_sensor.py +++ b/scripts/demos/sensors/contact_sensor.py @@ -24,9 +24,9 @@ """Rest everything follows.""" import torch +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg import isaaclab.sim as sim_utils -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.assets import AssetBaseCfg, RigidObjectCfg from isaaclab.scene import InteractiveScene, InteractiveSceneCfg from isaaclab.sensors import ContactSensorCfg diff --git a/scripts/demos/sensors/frame_transformer_sensor.py b/scripts/demos/sensors/frame_transformer_sensor.py index 12658679ee5..e97bf446dae 100644 --- a/scripts/demos/sensors/frame_transformer_sensor.py +++ b/scripts/demos/sensors/frame_transformer_sensor.py @@ -22,9 +22,9 @@ """Rest everything follows.""" import torch +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg import isaaclab.sim as sim_utils -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.assets import AssetBaseCfg, RigidObjectCfg from isaaclab.scene import InteractiveScene, InteractiveSceneCfg from isaaclab.sensors import FrameTransformerCfg diff --git a/scripts/demos/sensors/imu_sensor.py b/scripts/demos/sensors/imu_sensor.py index 192dc6eeab3..e4e47d30799 100644 --- a/scripts/demos/sensors/imu_sensor.py +++ b/scripts/demos/sensors/imu_sensor.py @@ -24,9 +24,9 @@ """Rest everything follows.""" import torch +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg import isaaclab.sim as sim_utils -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.assets import AssetBaseCfg from isaaclab.scene import InteractiveScene, InteractiveSceneCfg from isaaclab.sensors import ImuCfg diff --git a/scripts/demos/sensors/multi_mesh_raycaster.py b/scripts/demos/sensors/multi_mesh_raycaster.py index 04efd09d9f4..c8875f1dba8 100644 --- a/scripts/demos/sensors/multi_mesh_raycaster.py +++ b/scripts/demos/sensors/multi_mesh_raycaster.py @@ -47,12 +47,12 @@ import random import torch +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg import omni.usd from pxr import Gf, Sdf import isaaclab.sim as sim_utils -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.assets import Articulation, AssetBaseCfg, RigidObjectCfg from isaaclab.markers.config import VisualizationMarkersCfg from isaaclab.scene import InteractiveScene, InteractiveSceneCfg diff --git a/scripts/demos/sensors/multi_mesh_raycaster_camera.py b/scripts/demos/sensors/multi_mesh_raycaster_camera.py index dd376499984..0ef22ef6cc3 100644 --- a/scripts/demos/sensors/multi_mesh_raycaster_camera.py +++ b/scripts/demos/sensors/multi_mesh_raycaster_camera.py @@ -47,12 +47,12 @@ import random import torch +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg import omni.usd from pxr import Gf, Sdf import isaaclab.sim as sim_utils -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.assets import Articulation, AssetBaseCfg, RigidObjectCfg from isaaclab.markers.config import VisualizationMarkersCfg from isaaclab.scene import InteractiveScene, InteractiveSceneCfg diff --git a/scripts/demos/sensors/raycaster_sensor.py b/scripts/demos/sensors/raycaster_sensor.py index 7322df0c883..8e4c1343c4c 100644 --- a/scripts/demos/sensors/raycaster_sensor.py +++ b/scripts/demos/sensors/raycaster_sensor.py @@ -23,9 +23,9 @@ import numpy as np import torch +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg import isaaclab.sim as sim_utils -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.assets import AssetBaseCfg from isaaclab.scene import InteractiveScene, InteractiveSceneCfg from isaaclab.sensors.ray_caster import RayCasterCfg, patterns diff --git a/scripts/tools/check_instanceable.py b/scripts/tools/check_instanceable.py index b3176c24c24..a61e33b7984 100644 --- a/scripts/tools/check_instanceable.py +++ b/scripts/tools/check_instanceable.py @@ -64,10 +64,11 @@ """Rest everything follows.""" +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg + from isaacsim.core.cloner import GridCloner import isaaclab.sim as sim_utils -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sim import SimulationCfg, SimulationContext from isaaclab.utils import Timer from isaaclab.utils.assets import check_file_path diff --git a/scripts/tutorials/00_sim/create_empty.py b/scripts/tutorials/00_sim/create_empty.py index 5f207b82b69..67e634e96d7 100644 --- a/scripts/tutorials/00_sim/create_empty.py +++ b/scripts/tutorials/00_sim/create_empty.py @@ -32,6 +32,7 @@ """Rest everything follows.""" from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg + from isaaclab.sim import SimulationCfg, SimulationContext diff --git a/scripts/tutorials/00_sim/launch_app.py b/scripts/tutorials/00_sim/launch_app.py index 7437b6cd580..ee70497e733 100644 --- a/scripts/tutorials/00_sim/launch_app.py +++ b/scripts/tutorials/00_sim/launch_app.py @@ -41,9 +41,10 @@ """Rest everything follows.""" -import isaaclab.sim as sim_utils from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +import isaaclab.sim as sim_utils + def design_scene(): """Designs the scene by spawning ground plane, light, objects and meshes from usd files.""" diff --git a/scripts/tutorials/00_sim/log_time.py b/scripts/tutorials/00_sim/log_time.py index 25b6964c46b..d0d0431d051 100644 --- a/scripts/tutorials/00_sim/log_time.py +++ b/scripts/tutorials/00_sim/log_time.py @@ -35,6 +35,7 @@ """Rest everything follows.""" from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg + from isaaclab.sim import SimulationCfg, SimulationContext diff --git a/scripts/tutorials/00_sim/spawn_prims.py b/scripts/tutorials/00_sim/spawn_prims.py index 1caa8396c79..08cf100b36a 100644 --- a/scripts/tutorials/00_sim/spawn_prims.py +++ b/scripts/tutorials/00_sim/spawn_prims.py @@ -31,8 +31,9 @@ """Rest everything follows.""" -import isaaclab.sim as sim_utils from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg + +import isaaclab.sim as sim_utils from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR diff --git a/scripts/tutorials/04_sensors/add_sensors_on_robot.py b/scripts/tutorials/04_sensors/add_sensors_on_robot.py index c6d784ed943..8188016eb96 100644 --- a/scripts/tutorials/04_sensors/add_sensors_on_robot.py +++ b/scripts/tutorials/04_sensors/add_sensors_on_robot.py @@ -40,10 +40,10 @@ """Rest everything follows.""" import torch +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg import isaaclab.sim as sim_utils from isaaclab.assets import ArticulationCfg, AssetBaseCfg -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.scene import InteractiveScene, InteractiveSceneCfg from isaaclab.sensors import CameraCfg, ContactSensorCfg, RayCasterCfg, patterns from isaaclab.utils import configclass diff --git a/scripts/tutorials/04_sensors/run_frame_transformer.py b/scripts/tutorials/04_sensors/run_frame_transformer.py index a6d98da8dc0..661de27bdc7 100644 --- a/scripts/tutorials/04_sensors/run_frame_transformer.py +++ b/scripts/tutorials/04_sensors/run_frame_transformer.py @@ -35,6 +35,7 @@ import math import torch +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg import isaacsim.util.debug_draw._debug_draw as omni_debug_draw @@ -43,7 +44,6 @@ from isaaclab.assets import Articulation from isaaclab.markers import VisualizationMarkers from isaaclab.markers.config import FRAME_MARKER_CFG -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sensors import FrameTransformer, FrameTransformerCfg, OffsetCfg from isaaclab.sim import SimulationContext diff --git a/scripts/tutorials/04_sensors/run_usd_camera.py b/scripts/tutorials/04_sensors/run_usd_camera.py index fb57e01b9e7..9b7ccc232d7 100644 --- a/scripts/tutorials/04_sensors/run_usd_camera.py +++ b/scripts/tutorials/04_sensors/run_usd_camera.py @@ -248,7 +248,11 @@ def run_simulator(sim: sim_utils.SimulationContext, scene_entities: dict): rep_writer.write(rep_output) # Draw pointcloud if there is a GUI and --draw has been passed - if sim.carb_settings.get("/isaaclab/has_gui") and args_cli.draw and "distance_to_image_plane" in camera.data.output.keys(): + if ( + sim.carb_settings.get("/isaaclab/has_gui") + and args_cli.draw + and "distance_to_image_plane" in camera.data.output.keys() + ): # Derive pointcloud from camera at camera_index pointcloud = create_pointcloud_from_depth( intrinsic_matrix=camera.data.intrinsic_matrices[camera_index], diff --git a/scripts/tutorials/05_controllers/run_diff_ik.py b/scripts/tutorials/05_controllers/run_diff_ik.py index 6b34660f63a..2a66e334526 100644 --- a/scripts/tutorials/05_controllers/run_diff_ik.py +++ b/scripts/tutorials/05_controllers/run_diff_ik.py @@ -38,11 +38,11 @@ """Rest everything follows.""" import torch +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg import isaaclab.sim as sim_utils from isaaclab.assets import AssetBaseCfg from isaaclab.controllers import DifferentialIKController, DifferentialIKControllerCfg -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.managers import SceneEntityCfg from isaaclab.markers import VisualizationMarkers from isaaclab.markers.config import FRAME_MARKER_CFG diff --git a/scripts/tutorials/05_controllers/run_osc.py b/scripts/tutorials/05_controllers/run_osc.py index 95dbca5ee7f..7116f2b049c 100644 --- a/scripts/tutorials/05_controllers/run_osc.py +++ b/scripts/tutorials/05_controllers/run_osc.py @@ -37,11 +37,11 @@ """Rest everything follows.""" import torch +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg import isaaclab.sim as sim_utils from isaaclab.assets import Articulation, AssetBaseCfg from isaaclab.controllers import OperationalSpaceController, OperationalSpaceControllerCfg -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.markers import VisualizationMarkers from isaaclab.markers.config import FRAME_MARKER_CFG from isaaclab.scene import InteractiveScene, InteractiveSceneCfg diff --git a/source/isaaclab/isaaclab/assets/asset_base.py b/source/isaaclab/isaaclab/assets/asset_base.py index 547bfc22708..5342a42699f 100644 --- a/source/isaaclab/isaaclab/assets/asset_base.py +++ b/source/isaaclab/isaaclab/assets/asset_base.py @@ -13,12 +13,12 @@ from typing import TYPE_CHECKING, Any import torch +from isaaclab_physx.physics import IsaacEvents, PhysxManager import omni.kit.app import isaaclab.sim as sim_utils from isaaclab.physics import PhysicsEvent, PhysicsManager -from isaaclab_physx.physics import IsaacEvents, PhysxManager from isaaclab.sim.utils.stage import get_current_stage if TYPE_CHECKING: diff --git a/source/isaaclab/isaaclab/envs/direct_marl_env.py b/source/isaaclab/isaaclab/envs/direct_marl_env.py index f47f09d537e..1664d11e258 100644 --- a/source/isaaclab/isaaclab/envs/direct_marl_env.py +++ b/source/isaaclab/isaaclab/envs/direct_marl_env.py @@ -375,7 +375,9 @@ def step(self, actions: dict[AgentID, ActionType]) -> EnvStepReturn: # check if we need to do rendering within the physics loop # note: checked here once to avoid multiple checks within the loop - is_rendering = self.sim.carb_settings.get("/isaaclab/has_gui") or self.sim.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") + is_rendering = self.sim.carb_settings.get("/isaaclab/has_gui") or self.sim.carb_settings.get_as_bool( + "/isaaclab/render/rtx_sensors" + ) # perform physics stepping for _ in range(self.cfg.decimation): @@ -500,7 +502,9 @@ def render(self, recompute: bool = False) -> np.ndarray | None: return None elif self.render_mode == "rgb_array": # check that if any render could have happened - if not self.sim.carb_settings.get("/isaaclab/has_gui") and not bool(self.sim.carb_settings.get("/isaaclab/render/offscreen")): + if not self.sim.carb_settings.get("/isaaclab/has_gui") and not bool( + self.sim.carb_settings.get("/isaaclab/render/offscreen") + ): raise RuntimeError( f"Cannot render '{self.render_mode}' - no GUI and offscreen rendering not enabled." " If running headless, make sure --enable_cameras is set." diff --git a/source/isaaclab/isaaclab/envs/direct_rl_env.py b/source/isaaclab/isaaclab/envs/direct_rl_env.py index 94f86ba9093..f3595939b14 100644 --- a/source/isaaclab/isaaclab/envs/direct_rl_env.py +++ b/source/isaaclab/isaaclab/envs/direct_rl_env.py @@ -366,7 +366,9 @@ def step(self, action: torch.Tensor) -> VecEnvStepReturn: # check if we need to do rendering within the physics loop # note: checked here once to avoid multiple checks within the loop - is_rendering = self.sim.carb_settings.get("/isaaclab/has_gui") or self.sim.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") + is_rendering = self.sim.carb_settings.get("/isaaclab/has_gui") or self.sim.carb_settings.get_as_bool( + "/isaaclab/render/rtx_sensors" + ) # perform physics stepping for _ in range(self.cfg.decimation): @@ -399,7 +401,10 @@ def step(self, action: torch.Tensor) -> VecEnvStepReturn: if len(reset_env_ids) > 0: self._reset_idx(reset_env_ids) # if sensors are added to the scene, make sure we render to reflect changes in reset - if self.sim.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") and self.cfg.num_rerenders_on_reset > 0: + if ( + self.sim.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") + and self.cfg.num_rerenders_on_reset > 0 + ): for _ in range(self.cfg.num_rerenders_on_reset): self.sim.render() @@ -470,7 +475,9 @@ def render(self, recompute: bool = False) -> np.ndarray | None: return None elif self.render_mode == "rgb_array": # check that if any render could have happened - if not self.sim.carb_settings.get("/isaaclab/has_gui") and not bool(self.sim.carb_settings.get("/isaaclab/render/offscreen")): + if not self.sim.carb_settings.get("/isaaclab/has_gui") and not bool( + self.sim.carb_settings.get("/isaaclab/render/offscreen") + ): raise RuntimeError( f"Cannot render '{self.render_mode}' - no GUI and offscreen rendering not enabled." " If running headless, make sure --enable_cameras is set." diff --git a/source/isaaclab/isaaclab/envs/manager_based_env.py b/source/isaaclab/isaaclab/envs/manager_based_env.py index 60718b46f44..7461dd27042 100644 --- a/source/isaaclab/isaaclab/envs/manager_based_env.py +++ b/source/isaaclab/isaaclab/envs/manager_based_env.py @@ -473,7 +473,9 @@ def step(self, action: torch.Tensor) -> tuple[VecEnvObs, dict]: # check if we need to do rendering within the physics loop # note: checked here once to avoid multiple checks within the loop - is_rendering = self.sim.carb_settings.get("/isaaclab/has_gui") or self.sim.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") + is_rendering = self.sim.carb_settings.get("/isaaclab/has_gui") or self.sim.carb_settings.get_as_bool( + "/isaaclab/render/rtx_sensors" + ) # perform physics stepping for _ in range(self.cfg.decimation): diff --git a/source/isaaclab/isaaclab/envs/manager_based_rl_env.py b/source/isaaclab/isaaclab/envs/manager_based_rl_env.py index efd93f53637..86ad11a104c 100644 --- a/source/isaaclab/isaaclab/envs/manager_based_rl_env.py +++ b/source/isaaclab/isaaclab/envs/manager_based_rl_env.py @@ -176,7 +176,9 @@ def step(self, action: torch.Tensor) -> VecEnvStepReturn: # check if we need to do rendering within the physics loop # note: checked here once to avoid multiple checks within the loop - is_rendering = self.sim.carb_settings.get("/isaaclab/has_gui") or self.sim.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") + is_rendering = self.sim.carb_settings.get("/isaaclab/has_gui") or self.sim.carb_settings.get_as_bool( + "/isaaclab/render/rtx_sensors" + ) # perform physics stepping for _ in range(self.cfg.decimation): @@ -221,7 +223,10 @@ def step(self, action: torch.Tensor) -> VecEnvStepReturn: self._reset_idx(reset_env_ids) # if sensors are added to the scene, make sure we render to reflect changes in reset - if self.sim.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") and self.cfg.num_rerenders_on_reset > 0: + if ( + self.sim.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") + and self.cfg.num_rerenders_on_reset > 0 + ): for _ in range(self.cfg.num_rerenders_on_reset): self.sim.render() @@ -271,7 +276,9 @@ def render(self, recompute: bool = False) -> np.ndarray | None: return None elif self.render_mode == "rgb_array": # check that if any render could have happened - if not self.sim.carb_settings.get("/isaaclab/has_gui") and not bool(self.sim.carb_settings.get("/isaaclab/render/offscreen")): + if not self.sim.carb_settings.get("/isaaclab/has_gui") and not bool( + self.sim.carb_settings.get("/isaaclab/render/offscreen") + ): raise RuntimeError( f"Cannot render '{self.render_mode}' - no GUI and offscreen rendering not enabled." " If running headless, make sure --enable_cameras is set." diff --git a/source/isaaclab/isaaclab/envs/ui/base_env_window.py b/source/isaaclab/isaaclab/envs/ui/base_env_window.py index e0f2e122911..e3b071054f2 100644 --- a/source/isaaclab/isaaclab/envs/ui/base_env_window.py +++ b/source/isaaclab/isaaclab/envs/ui/base_env_window.py @@ -139,7 +139,9 @@ def _build_sim_frame(self): **record_animate_cfg ) # disable the button if fabric is not enabled - self.ui_window_elements["record_animation"].enabled = not self.env.sim.get_setting("/isaaclab/fabric_enabled") + self.ui_window_elements["record_animation"].enabled = not self.env.sim.get_setting( + "/isaaclab/fabric_enabled" + ) def _build_viewer_frame(self): """Build the viewer-related control frame for the UI.""" diff --git a/source/isaaclab/isaaclab/physics/physics_manager.py b/source/isaaclab/isaaclab/physics/physics_manager.py index 3d23cd6a148..e2820c3ed0b 100644 --- a/source/isaaclab/isaaclab/physics/physics_manager.py +++ b/source/isaaclab/isaaclab/physics/physics_manager.py @@ -10,8 +10,9 @@ import logging import weakref from abc import ABC, abstractmethod +from collections.abc import Callable from enum import Enum -from typing import TYPE_CHECKING, Any, Callable, ClassVar +from typing import TYPE_CHECKING, Any, ClassVar if TYPE_CHECKING: from isaaclab.sim.simulation_context import SimulationContext @@ -54,7 +55,7 @@ class PhysicsEvent(Enum): class CallbackHandle: """Handle for a registered callback, allowing deregistration.""" - def __init__(self, callback_id: int, manager: type["PhysicsManager"]): + def __init__(self, callback_id: int, manager: type[PhysicsManager]): self._id = callback_id self._manager = manager @@ -81,7 +82,7 @@ class PhysicsManager(ABC): Lifecycle: initialize() -> reset() -> step() (repeated) -> close() """ - _sim: ClassVar["SimulationContext | None"] = None + _sim: ClassVar[SimulationContext | None] = None _cfg: ClassVar[Any] = None _device: ClassVar[str] = "cuda:0" _sim_time: ClassVar[float] = 0.0 @@ -113,10 +114,7 @@ def register_callback( Example: >>> def on_physics_ready(payload): ... print("Physics is ready!") - >>> handle = PhysxManager.register_callback( - ... on_physics_ready, - ... PhysicsEvent.PHYSICS_READY - ... ) + >>> handle = PhysxManager.register_callback(on_physics_ready, PhysicsEvent.PHYSICS_READY) >>> # Later, to remove: >>> handle.deregister() """ @@ -156,11 +154,7 @@ def dispatch_event(cls, event: PhysicsEvent, payload: Any = None) -> None: event: The event to dispatch. payload: Optional data to pass to callbacks. """ - matching = [ - (cid, cb, order) - for cid, (ev, cb, order, name, sub) in cls._callbacks.items() - if ev == event - ] + matching = [(cid, cb, order) for cid, (ev, cb, order, name, sub) in cls._callbacks.items() if ev == event] matching.sort(key=lambda x: x[2]) for cid, callback, order in matching: @@ -245,7 +239,7 @@ def _unsubscribe_from_event( @classmethod @abstractmethod - def initialize(cls, sim_context: "SimulationContext") -> None: + def initialize(cls, sim_context: SimulationContext) -> None: """Initialize the physics manager with simulation context. Subclasses should call super().initialize() first, then do backend-specific setup. diff --git a/source/isaaclab/isaaclab/physics/physics_manager_cfg.py b/source/isaaclab/isaaclab/physics/physics_manager_cfg.py index d898a4769d8..e400d984ced 100644 --- a/source/isaaclab/isaaclab/physics/physics_manager_cfg.py +++ b/source/isaaclab/isaaclab/physics/physics_manager_cfg.py @@ -7,12 +7,11 @@ from __future__ import annotations -from typing import TYPE_CHECKING - from dataclasses import MISSING +from typing import TYPE_CHECKING -from isaaclab.utils import configclass from isaaclab.sim.spawners.materials import RigidBodyMaterialCfg +from isaaclab.utils import configclass if TYPE_CHECKING: from .physics_manager import PhysicsManager diff --git a/source/isaaclab/isaaclab/sensors/ray_caster/ray_caster.py b/source/isaaclab/isaaclab/sensors/ray_caster/ray_caster.py index 469dd40a991..bf48c50a447 100644 --- a/source/isaaclab/isaaclab/sensors/ray_caster/ray_caster.py +++ b/source/isaaclab/isaaclab/sensors/ray_caster/ray_caster.py @@ -18,9 +18,9 @@ from pxr import UsdGeom, UsdPhysics import isaaclab.sim as sim_utils -from isaaclab.physics import PhysicsManager import isaaclab.utils.math as math_utils from isaaclab.markers import VisualizationMarkers +from isaaclab.physics import PhysicsManager from isaaclab.sim.views import XformPrimView from isaaclab.terrains.trimesh.utils import make_plane from isaaclab.utils.math import quat_apply, quat_apply_yaw diff --git a/source/isaaclab/isaaclab/sensors/sensor_base.py b/source/isaaclab/isaaclab/sensors/sensor_base.py index df4102be48c..9bead099e8c 100644 --- a/source/isaaclab/isaaclab/sensors/sensor_base.py +++ b/source/isaaclab/isaaclab/sensors/sensor_base.py @@ -19,12 +19,12 @@ from typing import TYPE_CHECKING, Any import torch +from isaaclab_physx.physics import IsaacEvents, PhysxManager import omni.kit.app import isaaclab.sim as sim_utils -from isaaclab.physics import PhysicsEvent, PhysicsManager -from isaaclab_physx.physics import IsaacEvents, PhysxManager +from isaaclab.physics import PhysicsEvent from isaaclab.sim.utils.stage import get_current_stage if TYPE_CHECKING: diff --git a/source/isaaclab/isaaclab/sim/simulation_cfg.py b/source/isaaclab/isaaclab/sim/simulation_cfg.py index b6a869b3e8f..c679d0c89e4 100644 --- a/source/isaaclab/isaaclab/sim/simulation_cfg.py +++ b/source/isaaclab/isaaclab/sim/simulation_cfg.py @@ -9,13 +9,14 @@ configuring the environment instances, viewer settings, and simulation parameters. """ +import contextlib import warnings from typing import Any, Literal # Literal used by RenderCfg -from isaaclab.utils import configclass +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.physics.physics_manager_cfg import PhysicsManagerCfg -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab.utils import configclass from isaaclab.visualizers import VisualizerCfg @@ -63,8 +64,9 @@ class RenderCfg: """ enable_translucency: bool | None = None - """Enables translucency for specular transmissive surfaces such as glass at the cost of some performance. Default is False. + """Enables translucency for specular transmissive surfaces such as glass. + This comes at the cost of some performance. Default is False. This is set by the variable: ``/rtx/translucency/enabled``. """ @@ -86,8 +88,9 @@ class RenderCfg: - **DLSS**: Boosts performance by using AI to output higher resolution frames from a lower resolution input. DLSS samples multiple lower resolution images and uses motion data and feedback from prior frames to reconstruct native quality images. - - **DLAA**: Provides higher image quality with an AI-based anti-aliasing technique. DLAA uses the same Super Resolution - technology developed for DLSS, reconstructing a native resolution image to maximize image quality. + - **DLAA**: Provides higher image quality with an AI-based anti-aliasing technique. DLAA uses the same + Super Resolution technology developed for DLSS, reconstructing a native resolution image to maximize + image quality. This is set by the variable: ``/rtx/post/dlss/execMode``. """ @@ -178,8 +181,8 @@ class RenderCfg: """A general dictionary for users to supply all carb rendering settings with native names. The keys of the dictionary can be formatted like a carb setting, .kit file setting, or python variable. - For instance, a key value pair can be ``/rtx/translucency/enabled: False`` (carb), ``rtx.translucency.enabled: False`` (.kit), - or ``rtx_translucency_enabled: False`` (python). + For instance, a key value pair can be ``/rtx/translucency/enabled: False`` (carb), + ``rtx.translucency.enabled: False`` (.kit), or ``rtx_translucency_enabled: False`` (python). """ rendering_mode: Literal["performance", "balanced", "quality"] | None = None @@ -285,7 +288,7 @@ class SimulationCfg: physx: Any | None = None """DEPRECATED: Use physics_manager_cfg (PhysxManagerCfg) directly instead. - + After initialization, this field is set to physics_manager_cfg for backward compatibility. """ @@ -311,10 +314,8 @@ def __post_init__(self): # This allows runtime access like self.sim.dt to work via __getattr__ for field_name in deprecated_fields: if field_name != "physics_material": # physics_material needs object access - try: + with contextlib.suppress(AttributeError): delattr(self, field_name) - except AttributeError: - pass # Set physics_material to point to physics_manager_cfg.physics_material for backward-compatible access if hasattr(self.physics_manager_cfg, "physics_material"): @@ -395,8 +396,7 @@ def __setattr__(self, name: str, value: Any) -> None: if hasattr(physics_cfg, name): setattr(physics_cfg, name, value) warnings.warn( - f"SimulationCfg.{name} is deprecated. " - f"Use {deprecated_map[name]} instead.", + f"SimulationCfg.{name} is deprecated. Use {deprecated_map[name]} instead.", DeprecationWarning, stacklevel=2, ) @@ -423,8 +423,7 @@ def __getattr__(self, name: str) -> Any: physics_cfg = object.__getattribute__(self, "physics_manager_cfg") if hasattr(physics_cfg, name): warnings.warn( - f"SimulationCfg.{name} is deprecated. " - f"Use {deprecated_map[name]} instead.", + f"SimulationCfg.{name} is deprecated. Use {deprecated_map[name]} instead.", DeprecationWarning, stacklevel=2, ) diff --git a/source/isaaclab/isaaclab/sim/simulation_context.py b/source/isaaclab/isaaclab/sim/simulation_context.py index 572a63aaf8d..010a1151527 100644 --- a/source/isaaclab/isaaclab/sim/simulation_context.py +++ b/source/isaaclab/isaaclab/sim/simulation_context.py @@ -10,16 +10,17 @@ from contextlib import contextmanager from typing import Any -import carb import torch -from pxr import Gf, Usd, UsdGeom, UsdPhysics, UsdUtils -import isaaclab.sim.utils.stage as stage_utils +import carb +from pxr import Gf, Usd, UsdGeom, UsdPhysics, UsdUtils import isaaclab.sim as sim_utils +import isaaclab.sim.utils.stage as stage_utils from isaaclab.physics import PhysicsManager from isaaclab.sim.utils import create_new_stage_in_memory from isaaclab.visualizers import Visualizer + from .simulation_cfg import SimulationCfg from .spawners import DomeLightCfg, GroundPlaneCfg @@ -187,6 +188,7 @@ def _init_visualizers(self) -> None: # Get or create visualizer configs cfg_list = self.cfg.visualizer_cfgs from isaaclab_physx.visualizers import PhysxOVVisualizerCfg + type_map = {"omniverse": PhysxOVVisualizerCfg} viz_cfgs = [] if cfg_list is None: diff --git a/source/isaaclab/test/app/test_non_headless_launch.py b/source/isaaclab/test/app/test_non_headless_launch.py index 9c4df46eca6..03f591ea272 100644 --- a/source/isaaclab/test/app/test_non_headless_launch.py +++ b/source/isaaclab/test/app/test_non_headless_launch.py @@ -20,9 +20,10 @@ """Rest everything follows.""" +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg + import isaaclab.sim as sim_utils from isaaclab.assets import AssetBaseCfg -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.scene import InteractiveScene, InteractiveSceneCfg from isaaclab.utils import configclass diff --git a/source/isaaclab/test/assets/check_external_force.py b/source/isaaclab/test/assets/check_external_force.py index 8f0f7a29a11..96a5213e200 100644 --- a/source/isaaclab/test/assets/check_external_force.py +++ b/source/isaaclab/test/assets/check_external_force.py @@ -37,10 +37,10 @@ """Rest everything follows.""" import torch +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg import isaaclab.sim as sim_utils from isaaclab.assets import Articulation -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sim import SimulationContext ## diff --git a/source/isaaclab/test/assets/check_fixed_base_assets.py b/source/isaaclab/test/assets/check_fixed_base_assets.py index 454e67fe429..ccd92739bef 100644 --- a/source/isaaclab/test/assets/check_fixed_base_assets.py +++ b/source/isaaclab/test/assets/check_fixed_base_assets.py @@ -34,10 +34,10 @@ import numpy as np import torch +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg import isaaclab.sim as sim_utils from isaaclab.assets import Articulation -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg ## # Pre-defined configs diff --git a/source/isaaclab/test/controllers/test_differential_ik.py b/source/isaaclab/test/controllers/test_differential_ik.py index 9e6ef349a1d..cd75ca9da38 100644 --- a/source/isaaclab/test/controllers/test_differential_ik.py +++ b/source/isaaclab/test/controllers/test_differential_ik.py @@ -14,13 +14,13 @@ import pytest import torch +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaacsim.core.cloner import GridCloner import isaaclab.sim as sim_utils from isaaclab.assets import Articulation from isaaclab.controllers import DifferentialIKController, DifferentialIKControllerCfg -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.utils.math import ( # isort:skip compute_pose_error, diff --git a/source/isaaclab/test/controllers/test_operational_space.py b/source/isaaclab/test/controllers/test_operational_space.py index d424dc34b62..2a7cab03908 100644 --- a/source/isaaclab/test/controllers/test_operational_space.py +++ b/source/isaaclab/test/controllers/test_operational_space.py @@ -15,13 +15,13 @@ import pytest import torch from flaky import flaky +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaacsim.core.cloner import GridCloner import isaaclab.sim as sim_utils from isaaclab.assets import Articulation from isaaclab.controllers import OperationalSpaceController, OperationalSpaceControllerCfg -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.markers import VisualizationMarkers from isaaclab.markers.config import FRAME_MARKER_CFG from isaaclab.sensors import ContactSensor, ContactSensorCfg diff --git a/source/isaaclab/test/devices/check_keyboard.py b/source/isaaclab/test/devices/check_keyboard.py index 0a6583936f4..99fcfa57507 100644 --- a/source/isaaclab/test/devices/check_keyboard.py +++ b/source/isaaclab/test/devices/check_keyboard.py @@ -23,8 +23,9 @@ import ctypes -from isaaclab.devices import Se3Keyboard, Se3KeyboardCfg from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg + +from isaaclab.devices import Se3Keyboard, Se3KeyboardCfg from isaaclab.sim import SimulationCfg, SimulationContext diff --git a/source/isaaclab/test/envs/test_env_rendering_logic.py b/source/isaaclab/test/envs/test_env_rendering_logic.py index 7ac437ae3c7..ce39c5ab76a 100644 --- a/source/isaaclab/test/envs/test_env_rendering_logic.py +++ b/source/isaaclab/test/envs/test_env_rendering_logic.py @@ -15,6 +15,7 @@ import pytest import torch +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg import omni.usd @@ -27,7 +28,6 @@ ManagerBasedRLEnvCfg, ) from isaaclab.scene import InteractiveSceneCfg -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sim import SimulationCfg, SimulationContext from isaaclab.utils import configclass @@ -48,7 +48,9 @@ class EnvCfg(ManagerBasedEnvCfg): decimation: int = 4 episode_length_s: float = 100.0 - sim: SimulationCfg = SimulationCfg(render_interval=render_interval, physics_manager_cfg=PhysxManagerCfg(dt=0.005)) + sim: SimulationCfg = SimulationCfg( + render_interval=render_interval, physics_manager_cfg=PhysxManagerCfg(dt=0.005) + ) scene: InteractiveSceneCfg = InteractiveSceneCfg(num_envs=1, env_spacing=1.0) actions: EmptyManagerCfg = EmptyManagerCfg() observations: EmptyManagerCfg = EmptyManagerCfg() @@ -65,7 +67,9 @@ class EnvCfg(ManagerBasedRLEnvCfg): decimation: int = 4 episode_length_s: float = 100.0 - sim: SimulationCfg = SimulationCfg(render_interval=render_interval, physics_manager_cfg=PhysxManagerCfg(dt=0.005)) + sim: SimulationCfg = SimulationCfg( + render_interval=render_interval, physics_manager_cfg=PhysxManagerCfg(dt=0.005) + ) scene: InteractiveSceneCfg = InteractiveSceneCfg(num_envs=1, env_spacing=1.0) actions: EmptyManagerCfg = EmptyManagerCfg() observations: EmptyManagerCfg = EmptyManagerCfg() @@ -86,7 +90,9 @@ class EnvCfg(DirectRLEnvCfg): action_space: int = 0 observation_space: int = 0 episode_length_s: float = 100.0 - sim: SimulationCfg = SimulationCfg(render_interval=render_interval, physics_manager_cfg=PhysxManagerCfg(dt=0.005)) + sim: SimulationCfg = SimulationCfg( + render_interval=render_interval, physics_manager_cfg=PhysxManagerCfg(dt=0.005) + ) scene: InteractiveSceneCfg = InteractiveSceneCfg(num_envs=1, env_spacing=1.0) class Env(DirectRLEnv): diff --git a/source/isaaclab/test/managers/test_observation_manager.py b/source/isaaclab/test/managers/test_observation_manager.py index 4bb2f8a687c..5285d31f818 100644 --- a/source/isaaclab/test/managers/test_observation_manager.py +++ b/source/isaaclab/test/managers/test_observation_manager.py @@ -20,9 +20,9 @@ import pytest import torch +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg import isaaclab.sim as sim_utils -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.managers import ( ManagerTermBase, ObservationGroupCfg, diff --git a/source/isaaclab/test/markers/check_markers_visibility.py b/source/isaaclab/test/markers/check_markers_visibility.py index 27752d39da9..84090d4cea9 100644 --- a/source/isaaclab/test/markers/check_markers_visibility.py +++ b/source/isaaclab/test/markers/check_markers_visibility.py @@ -38,9 +38,10 @@ """Rest everything follows.""" +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg + import isaaclab.sim as sim_utils from isaaclab.assets import ArticulationCfg, AssetBaseCfg -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.scene import InteractiveScene, InteractiveSceneCfg from isaaclab.sensors import RayCasterCfg, patterns from isaaclab.utils import configclass diff --git a/source/isaaclab/test/markers/test_visualization_markers.py b/source/isaaclab/test/markers/test_visualization_markers.py index cc8fe7cba35..158d02ed114 100644 --- a/source/isaaclab/test/markers/test_visualization_markers.py +++ b/source/isaaclab/test/markers/test_visualization_markers.py @@ -14,11 +14,11 @@ import pytest import torch +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg import isaaclab.sim as sim_utils from isaaclab.markers import VisualizationMarkers, VisualizationMarkersCfg from isaaclab.markers.config import FRAME_MARKER_CFG, POSITION_GOAL_MARKER_CFG -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sim import SimulationCfg, SimulationContext from isaaclab.utils.math import random_orientation from isaaclab.utils.timer import Timer diff --git a/source/isaaclab/test/scene/check_interactive_scene.py b/source/isaaclab/test/scene/check_interactive_scene.py index 8f4f609e752..c2635d6b8fa 100644 --- a/source/isaaclab/test/scene/check_interactive_scene.py +++ b/source/isaaclab/test/scene/check_interactive_scene.py @@ -27,9 +27,10 @@ """Rest everything follows.""" +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg + import isaaclab.sim as sim_utils from isaaclab.assets import AssetBaseCfg -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.scene import InteractiveScene, InteractiveSceneCfg from isaaclab.sensors.ray_caster import RayCasterCfg, patterns from isaaclab.sim import SimulationContext diff --git a/source/isaaclab/test/sensors/test_camera.py b/source/isaaclab/test/sensors/test_camera.py index a0f2a103303..6f44602051b 100644 --- a/source/isaaclab/test/sensors/test_camera.py +++ b/source/isaaclab/test/sensors/test_camera.py @@ -23,13 +23,13 @@ import pytest import scipy.spatial.transform as tf import torch +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg import omni.replicator.core as rep from isaacsim.core.prims import SingleGeometryPrim, SingleRigidPrim from pxr import Gf, Usd, UsdGeom import isaaclab.sim as sim_utils -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sensors.camera import Camera, CameraCfg from isaaclab.utils import convert_dict_to_backend from isaaclab.utils.timer import Timer diff --git a/source/isaaclab/test/sensors/test_multi_mesh_ray_caster_camera.py b/source/isaaclab/test/sensors/test_multi_mesh_ray_caster_camera.py index f738727458d..38e2faae0f8 100644 --- a/source/isaaclab/test/sensors/test_multi_mesh_ray_caster_camera.py +++ b/source/isaaclab/test/sensors/test_multi_mesh_ray_caster_camera.py @@ -21,12 +21,12 @@ import numpy as np import pytest import torch +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg import omni.replicator.core as rep from pxr import Gf import isaaclab.sim as sim_utils -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sensors.camera import Camera, CameraCfg from isaaclab.sensors.ray_caster import MultiMeshRayCasterCamera, MultiMeshRayCasterCameraCfg, patterns from isaaclab.sim import PinholeCameraCfg diff --git a/source/isaaclab/test/sensors/test_multi_tiled_camera.py b/source/isaaclab/test/sensors/test_multi_tiled_camera.py index b9753193b18..b3ef7e2552e 100644 --- a/source/isaaclab/test/sensors/test_multi_tiled_camera.py +++ b/source/isaaclab/test/sensors/test_multi_tiled_camera.py @@ -22,13 +22,13 @@ import pytest import torch from flaky import flaky +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg import omni.replicator.core as rep from isaacsim.core.prims import SingleGeometryPrim, SingleRigidPrim from pxr import Gf, UsdGeom import isaaclab.sim as sim_utils -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sensors.camera import TiledCamera, TiledCameraCfg diff --git a/source/isaaclab/test/sensors/test_ray_caster_camera.py b/source/isaaclab/test/sensors/test_ray_caster_camera.py index 3d925880e5c..abf64b653f7 100644 --- a/source/isaaclab/test/sensors/test_ray_caster_camera.py +++ b/source/isaaclab/test/sensors/test_ray_caster_camera.py @@ -21,12 +21,12 @@ import numpy as np import pytest import torch +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg import omni.replicator.core as rep from pxr import Gf import isaaclab.sim as sim_utils -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sensors.camera import Camera, CameraCfg from isaaclab.sensors.ray_caster import RayCasterCamera, RayCasterCameraCfg, patterns from isaaclab.sim import PinholeCameraCfg diff --git a/source/isaaclab/test/sensors/test_sensor_base.py b/source/isaaclab/test/sensors/test_sensor_base.py index e931d8a4e63..81fa3badefa 100644 --- a/source/isaaclab/test/sensors/test_sensor_base.py +++ b/source/isaaclab/test/sensors/test_sensor_base.py @@ -19,9 +19,9 @@ import pytest import torch +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg import isaaclab.sim as sim_utils -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sensors import SensorBase, SensorBaseCfg from isaaclab.utils import configclass diff --git a/source/isaaclab/test/sensors/test_tiled_camera.py b/source/isaaclab/test/sensors/test_tiled_camera.py index 08866777c28..d11092802cc 100644 --- a/source/isaaclab/test/sensors/test_tiled_camera.py +++ b/source/isaaclab/test/sensors/test_tiled_camera.py @@ -21,13 +21,13 @@ import numpy as np import pytest import torch +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg import omni.replicator.core as rep from isaacsim.core.prims import SingleGeometryPrim, SingleRigidPrim from pxr import Gf, UsdGeom import isaaclab.sim as sim_utils -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sensors.camera import Camera, CameraCfg, TiledCamera, TiledCameraCfg from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR from isaaclab.utils.timer import Timer diff --git a/source/isaaclab/test/sim/check_meshes.py b/source/isaaclab/test/sim/check_meshes.py index 121697f8eee..a68adda0f71 100644 --- a/source/isaaclab/test/sim/check_meshes.py +++ b/source/isaaclab/test/sim/check_meshes.py @@ -40,9 +40,9 @@ import numpy as np import torch import tqdm +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg import isaaclab.sim as sim_utils -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg def define_origins(num_origins: int, spacing: float) -> list[list[float]]: diff --git a/source/isaaclab/test/sim/test_mesh_converter.py b/source/isaaclab/test/sim/test_mesh_converter.py index fedf35a409a..5d6af838696 100644 --- a/source/isaaclab/test/sim/test_mesh_converter.py +++ b/source/isaaclab/test/sim/test_mesh_converter.py @@ -18,12 +18,12 @@ import tempfile import pytest +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg import omni from pxr import UsdGeom, UsdPhysics import isaaclab.sim as sim_utils -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sim import SimulationCfg, SimulationContext from isaaclab.sim.converters import MeshConverter, MeshConverterCfg from isaaclab.sim.schemas import MESH_APPROXIMATION_TOKENS, schemas_cfg diff --git a/source/isaaclab/test/sim/test_mjcf_converter.py b/source/isaaclab/test/sim/test_mjcf_converter.py index d78aee7ef39..37eb1e8d452 100644 --- a/source/isaaclab/test/sim/test_mjcf_converter.py +++ b/source/isaaclab/test/sim/test_mjcf_converter.py @@ -15,11 +15,11 @@ import os import pytest +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaacsim.core.utils.extensions import enable_extension, get_extension_path_from_name import isaaclab.sim as sim_utils -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sim import SimulationCfg, SimulationContext from isaaclab.sim.converters import MjcfConverter, MjcfConverterCfg diff --git a/source/isaaclab/test/sim/test_schemas.py b/source/isaaclab/test/sim/test_schemas.py index 40aecd369b6..b6ec6360edd 100644 --- a/source/isaaclab/test/sim/test_schemas.py +++ b/source/isaaclab/test/sim/test_schemas.py @@ -15,12 +15,12 @@ import math import pytest +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from pxr import UsdPhysics import isaaclab.sim as sim_utils import isaaclab.sim.schemas as schemas -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sim import SimulationCfg, SimulationContext from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR from isaaclab.utils.string import to_camel_case diff --git a/source/isaaclab/test/sim/test_simulation_context.py b/source/isaaclab/test/sim/test_simulation_context.py index e0a1f3b5297..a315ab2a0c6 100644 --- a/source/isaaclab/test/sim/test_simulation_context.py +++ b/source/isaaclab/test/sim/test_simulation_context.py @@ -12,15 +12,16 @@ """Rest everything follows.""" +import weakref + import numpy as np import pytest -import weakref +from isaaclab_physx.physics import IsaacEvents, PhysxManager, PhysxManagerCfg import omni.timeline import isaaclab.sim as sim_utils from isaaclab.sim import SimulationCfg, SimulationContext -from isaaclab_physx.physics import PhysxManager, PhysxManagerCfg, IsaacEvents @pytest.fixture(autouse=True) @@ -809,9 +810,7 @@ def on_prim_deletion(event): callback_state["deleted_path"] = event.payload.get("prim_path") # register callback for PRIM_DELETION event - callback_id = PhysxManager.register_callback( - lambda event: on_prim_deletion(event), event=IsaacEvents.PRIM_DELETION - ) + callback_id = PhysxManager.register_callback(lambda event: on_prim_deletion(event), event=IsaacEvents.PRIM_DELETION) try: # verify callback hasn't been called yet @@ -845,9 +844,7 @@ def on_timeline_stop(event): callback_state["timeline_stop_called"] = True # register callback for TIMELINE_STOP event - callback_id = PhysxManager.register_callback( - lambda event: on_timeline_stop(event), event=IsaacEvents.TIMELINE_STOP - ) + callback_id = PhysxManager.register_callback(lambda event: on_timeline_stop(event), event=IsaacEvents.TIMELINE_STOP) try: # verify callback hasn't been called yet diff --git a/source/isaaclab/test/sim/test_spawn_from_files.py b/source/isaaclab/test/sim/test_spawn_from_files.py index 2fd42661b8f..bb77eb2c3df 100644 --- a/source/isaaclab/test/sim/test_spawn_from_files.py +++ b/source/isaaclab/test/sim/test_spawn_from_files.py @@ -13,12 +13,12 @@ """Rest everything follows.""" import pytest +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from packaging.version import Version import omni.kit.app import isaaclab.sim as sim_utils -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sim import SimulationCfg, SimulationContext from isaaclab.utils.assets import ISAACLAB_NUCLEUS_DIR from isaaclab.utils.version import get_isaac_sim_version diff --git a/source/isaaclab/test/sim/test_spawn_lights.py b/source/isaaclab/test/sim/test_spawn_lights.py index 86d5c8262c4..152ef6d83a3 100644 --- a/source/isaaclab/test/sim/test_spawn_lights.py +++ b/source/isaaclab/test/sim/test_spawn_lights.py @@ -14,11 +14,11 @@ import pytest +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from pxr import Usd, UsdLux import isaaclab.sim as sim_utils -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sim import SimulationCfg, SimulationContext from isaaclab.utils.string import to_camel_case diff --git a/source/isaaclab/test/sim/test_spawn_materials.py b/source/isaaclab/test/sim/test_spawn_materials.py index 1e34375c596..28b3d33dbd0 100644 --- a/source/isaaclab/test/sim/test_spawn_materials.py +++ b/source/isaaclab/test/sim/test_spawn_materials.py @@ -14,11 +14,11 @@ import pytest +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from pxr import UsdPhysics, UsdShade import isaaclab.sim as sim_utils -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sim import SimulationCfg, SimulationContext from isaaclab.utils.assets import NVIDIA_NUCLEUS_DIR diff --git a/source/isaaclab/test/sim/test_spawn_meshes.py b/source/isaaclab/test/sim/test_spawn_meshes.py index 8ef59156789..beb3b7ff5db 100644 --- a/source/isaaclab/test/sim/test_spawn_meshes.py +++ b/source/isaaclab/test/sim/test_spawn_meshes.py @@ -14,9 +14,9 @@ import pytest +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg import isaaclab.sim as sim_utils -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sim import SimulationCfg, SimulationContext diff --git a/source/isaaclab/test/sim/test_spawn_sensors.py b/source/isaaclab/test/sim/test_spawn_sensors.py index 44571c095df..5672a364271 100644 --- a/source/isaaclab/test/sim/test_spawn_sensors.py +++ b/source/isaaclab/test/sim/test_spawn_sensors.py @@ -14,11 +14,11 @@ import pytest +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from pxr import Usd import isaaclab.sim as sim_utils -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sim import SimulationCfg, SimulationContext from isaaclab.sim.spawners.sensors.sensors import CUSTOM_FISHEYE_CAMERA_ATTRIBUTES, CUSTOM_PINHOLE_CAMERA_ATTRIBUTES from isaaclab.utils.string import to_camel_case diff --git a/source/isaaclab/test/sim/test_spawn_shapes.py b/source/isaaclab/test/sim/test_spawn_shapes.py index 525725960de..f77a113b36c 100644 --- a/source/isaaclab/test/sim/test_spawn_shapes.py +++ b/source/isaaclab/test/sim/test_spawn_shapes.py @@ -13,9 +13,9 @@ """Rest everything follows.""" import pytest +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg import isaaclab.sim as sim_utils -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sim import SimulationCfg, SimulationContext diff --git a/source/isaaclab/test/sim/test_spawn_wrappers.py b/source/isaaclab/test/sim/test_spawn_wrappers.py index 66bfa3c4dd8..2de1e3edaec 100644 --- a/source/isaaclab/test/sim/test_spawn_wrappers.py +++ b/source/isaaclab/test/sim/test_spawn_wrappers.py @@ -14,9 +14,9 @@ import pytest +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg import isaaclab.sim as sim_utils -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sim import SimulationCfg, SimulationContext from isaaclab.utils.assets import ISAACLAB_NUCLEUS_DIR diff --git a/source/isaaclab/test/sim/test_urdf_converter.py b/source/isaaclab/test/sim/test_urdf_converter.py index 4203d306d4f..806d049a8f9 100644 --- a/source/isaaclab/test/sim/test_urdf_converter.py +++ b/source/isaaclab/test/sim/test_urdf_converter.py @@ -16,13 +16,13 @@ import numpy as np import pytest +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from packaging.version import Version import omni.kit.app from isaacsim.core.prims import Articulation import isaaclab.sim as sim_utils -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sim import SimulationCfg, SimulationContext from isaaclab.sim.converters import UrdfConverter, UrdfConverterCfg from isaaclab.utils.version import get_isaac_sim_version diff --git a/source/isaaclab/test/sim/test_views_xform_prim.py b/source/isaaclab/test/sim/test_views_xform_prim.py index 43f31f52a27..ed5758a7326 100644 --- a/source/isaaclab/test/sim/test_views_xform_prim.py +++ b/source/isaaclab/test/sim/test_views_xform_prim.py @@ -20,8 +20,9 @@ except (ModuleNotFoundError, ImportError): _IsaacSimXformPrimView = None -import isaaclab.sim as sim_utils # noqa: E402 from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg # noqa: E402 + +import isaaclab.sim as sim_utils # noqa: E402 from isaaclab.sim.views import XformPrimView as XformPrimView # noqa: E402 from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR # noqa: E402 @@ -74,7 +75,9 @@ def _prim_type_for_backend(backend: str) -> str: def _create_view(pattern: str, device: str, backend: str) -> XformPrimView: """Create an XformPrimView for the requested backend.""" if backend == "fabric": - sim_utils.SimulationContext(sim_utils.SimulationCfg(device=device, physics_manager_cfg=PhysxManagerCfg(dt=0.01, use_fabric=True))) + sim_utils.SimulationContext( + sim_utils.SimulationCfg(device=device, physics_manager_cfg=PhysxManagerCfg(dt=0.01, use_fabric=True)) + ) return XformPrimView(pattern, device=device) diff --git a/source/isaaclab/test/visualization/check_scene_xr_visualization.py b/source/isaaclab/test/visualization/check_scene_xr_visualization.py index d367d28c36a..f67ebff0cb0 100644 --- a/source/isaaclab/test/visualization/check_scene_xr_visualization.py +++ b/source/isaaclab/test/visualization/check_scene_xr_visualization.py @@ -37,11 +37,12 @@ import time from typing import Any +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg + from pxr import Gf import isaaclab.sim as sim_utils from isaaclab.assets import AssetBaseCfg -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.scene import InteractiveScene, InteractiveSceneCfg from isaaclab.ui.xr_widgets import DataCollector, TriggerType, VisualizationManager, XRVisualization, update_instruction from isaaclab.utils import configclass diff --git a/source/isaaclab_contrib/test/sensors/test_visuotactile_sensor.py b/source/isaaclab_contrib/test/sensors/test_visuotactile_sensor.py index a9bba23b62d..0ac295ea06e 100644 --- a/source/isaaclab_contrib/test/sensors/test_visuotactile_sensor.py +++ b/source/isaaclab_contrib/test/sensors/test_visuotactile_sensor.py @@ -19,12 +19,12 @@ import pytest import torch +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg import omni.replicator.core as rep import isaaclab.sim as sim_utils from isaaclab.assets import Articulation, ArticulationCfg, RigidObject, RigidObjectCfg -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sensors.camera import TiledCameraCfg from isaaclab.terrains.trimesh.utils import make_plane from isaaclab.terrains.utils import create_prim_from_mesh diff --git a/source/isaaclab_physx/isaaclab_physx/assets/articulation/articulation.py b/source/isaaclab_physx/isaaclab_physx/assets/articulation/articulation.py index 2a5ded8c4c5..b1821544f08 100644 --- a/source/isaaclab_physx/isaaclab_physx/assets/articulation/articulation.py +++ b/source/isaaclab_physx/isaaclab_physx/assets/articulation/articulation.py @@ -17,7 +17,6 @@ import warp as wp from prettytable import PrettyTable -from isaaclab_physx.physics import PhysxManager as SimulationManager from pxr import PhysxSchema, UsdPhysics import isaaclab.utils.math as math_utils @@ -29,6 +28,8 @@ from isaaclab.utils.version import get_isaac_sim_version from isaaclab.utils.wrench_composer import WrenchComposer +from isaaclab_physx.physics import PhysxManager as SimulationManager + from .articulation_data import ArticulationData if TYPE_CHECKING: diff --git a/source/isaaclab_physx/isaaclab_physx/assets/articulation/articulation_data.py b/source/isaaclab_physx/isaaclab_physx/assets/articulation/articulation_data.py index bb6f21eb0de..6d442d76fb1 100644 --- a/source/isaaclab_physx/isaaclab_physx/assets/articulation/articulation_data.py +++ b/source/isaaclab_physx/isaaclab_physx/assets/articulation/articulation_data.py @@ -11,12 +11,12 @@ import torch -from isaaclab_physx.physics import PhysxManager as SimulationManager - from isaaclab.assets.articulation.base_articulation_data import BaseArticulationData from isaaclab.utils.buffers import TimestampedBuffer from isaaclab.utils.math import combine_frame_transforms, normalize, quat_apply, quat_apply_inverse +from isaaclab_physx.physics import PhysxManager as SimulationManager + if TYPE_CHECKING: from isaaclab.assets.articulation.articulation_view import ArticulationView diff --git a/source/isaaclab_physx/isaaclab_physx/assets/deformable_object/deformable_object.py b/source/isaaclab_physx/isaaclab_physx/assets/deformable_object/deformable_object.py index 40df6bbb85e..4eab7d588f6 100644 --- a/source/isaaclab_physx/isaaclab_physx/assets/deformable_object/deformable_object.py +++ b/source/isaaclab_physx/isaaclab_physx/assets/deformable_object/deformable_object.py @@ -12,7 +12,6 @@ import torch import omni.physics.tensors.impl.api as physx -from isaaclab_physx.physics import PhysxManager as SimulationManager from pxr import PhysxSchema, UsdShade import isaaclab.sim as sim_utils @@ -20,6 +19,8 @@ from isaaclab.assets.asset_base import AssetBase from isaaclab.markers import VisualizationMarkers +from isaaclab_physx.physics import PhysxManager as SimulationManager + from .deformable_object_data import DeformableObjectData if TYPE_CHECKING: diff --git a/source/isaaclab_physx/isaaclab_physx/assets/rigid_object/rigid_object.py b/source/isaaclab_physx/isaaclab_physx/assets/rigid_object/rigid_object.py index 5806f8cbc89..4f407f988e5 100644 --- a/source/isaaclab_physx/isaaclab_physx/assets/rigid_object/rigid_object.py +++ b/source/isaaclab_physx/isaaclab_physx/assets/rigid_object/rigid_object.py @@ -14,7 +14,6 @@ import warp as wp import omni.physics.tensors.impl.api as physx -from isaaclab_physx.physics import PhysxManager as SimulationManager from pxr import UsdPhysics import isaaclab.sim as sim_utils @@ -23,6 +22,8 @@ from isaaclab.assets.rigid_object.base_rigid_object import BaseRigidObject from isaaclab.utils.wrench_composer import WrenchComposer +from isaaclab_physx.physics import PhysxManager as SimulationManager + from .rigid_object_data import RigidObjectData if TYPE_CHECKING: diff --git a/source/isaaclab_physx/isaaclab_physx/assets/rigid_object/rigid_object_data.py b/source/isaaclab_physx/isaaclab_physx/assets/rigid_object/rigid_object_data.py index 7f3716b87d6..a29fedc34a2 100644 --- a/source/isaaclab_physx/isaaclab_physx/assets/rigid_object/rigid_object_data.py +++ b/source/isaaclab_physx/isaaclab_physx/assets/rigid_object/rigid_object_data.py @@ -11,8 +11,6 @@ import torch -from isaaclab_physx.physics import PhysxManager as SimulationManager - from isaaclab.assets.rigid_object.base_rigid_object_data import BaseRigidObjectData from isaaclab.utils.buffers import TimestampedBuffer from isaaclab.utils.math import ( @@ -22,6 +20,8 @@ quat_apply_inverse, ) +from isaaclab_physx.physics import PhysxManager as SimulationManager + if TYPE_CHECKING: from isaaclab.assets.rigid_object.rigid_object_view import RigidObjectView diff --git a/source/isaaclab_physx/isaaclab_physx/assets/rigid_object_collection/rigid_object_collection.py b/source/isaaclab_physx/isaaclab_physx/assets/rigid_object_collection/rigid_object_collection.py index 1c7b52075be..9d9e9e6bdd1 100644 --- a/source/isaaclab_physx/isaaclab_physx/assets/rigid_object_collection/rigid_object_collection.py +++ b/source/isaaclab_physx/isaaclab_physx/assets/rigid_object_collection/rigid_object_collection.py @@ -15,7 +15,6 @@ import warp as wp import omni.physics.tensors.impl.api as physx -from isaaclab_physx.physics import PhysxManager as SimulationManager from pxr import UsdPhysics import isaaclab.sim as sim_utils @@ -24,6 +23,8 @@ from isaaclab.assets.rigid_object_collection.base_rigid_object_collection import BaseRigidObjectCollection from isaaclab.utils.wrench_composer import WrenchComposer +from isaaclab_physx.physics import PhysxManager as SimulationManager + from .rigid_object_collection_data import RigidObjectCollectionData if TYPE_CHECKING: diff --git a/source/isaaclab_physx/isaaclab_physx/assets/rigid_object_collection/rigid_object_collection_data.py b/source/isaaclab_physx/isaaclab_physx/assets/rigid_object_collection/rigid_object_collection_data.py index dda885b78db..3c200cd1ef6 100644 --- a/source/isaaclab_physx/isaaclab_physx/assets/rigid_object_collection/rigid_object_collection_data.py +++ b/source/isaaclab_physx/isaaclab_physx/assets/rigid_object_collection/rigid_object_collection_data.py @@ -11,12 +11,12 @@ import torch -from isaaclab_physx.physics import PhysxManager as SimulationManager - from isaaclab.assets.rigid_object_collection.base_rigid_object_collection_data import BaseRigidObjectCollectionData from isaaclab.utils.buffers import TimestampedBuffer from isaaclab.utils.math import combine_frame_transforms, normalize, quat_apply, quat_apply_inverse +from isaaclab_physx.physics import PhysxManager as SimulationManager + if TYPE_CHECKING: from isaaclab.assets.rigid_object_collection.rigid_object_collection_view import RigidObjectCollectionView diff --git a/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py b/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py index 3b8fec86e70..811f6f3ba3a 100644 --- a/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py +++ b/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py @@ -15,9 +15,12 @@ import os import re import time +from collections.abc import Callable from datetime import datetime from enum import Enum -from typing import TYPE_CHECKING, Any, Callable, ClassVar +from typing import TYPE_CHECKING, Any, ClassVar + +import torch import carb import omni.kit.app @@ -25,12 +28,10 @@ import omni.physx import omni.timeline import omni.usd -import torch from pxr import PhysxSchema, Sdf import isaaclab.sim as sim_utils - -from isaaclab.physics import PhysicsManager, PhysicsEvent, CallbackHandle +from isaaclab.physics import CallbackHandle, PhysicsEvent, PhysicsManager if TYPE_CHECKING: from isaaclab.sim.simulation_context import SimulationContext @@ -124,8 +125,14 @@ def _finish(self) -> None: if ovd_files and self._physx_pvd: input_ovd = max(ovd_files, key=os.path.getctime) self._physx_pvd.ovd_to_usd_over_with_layer_creation( - input_ovd, stage_path, self._output_dir, "baked_animation_recording.usda", - self._start_time, self._stop_time, True, False + input_ovd, + stage_path, + self._output_dir, + "baked_animation_recording.usda", + self._start_time, + self._stop_time, + True, + False, ) self._update_usda_start_time(os.path.join(self._output_dir, "baked_animation_recording.usda")) @@ -150,7 +157,7 @@ class PhysxManager(PhysicsManager): Lifecycle: initialize() -> reset() -> step() (repeated) -> close() """ - _cfg: ClassVar["PhysxManagerCfg | None"] = None + _cfg: ClassVar[PhysxManagerCfg | None] = None _timeline: ClassVar[omni.timeline.ITimeline] = omni.timeline.get_timeline_interface() _event_bus: ClassVar[carb.eventdispatcher.IEventDispatcher] = carb.eventdispatcher.get_eventdispatcher() @@ -190,7 +197,7 @@ def __getattr__(self, name: str) -> Callable[..., Any]: _message_bus = _event_bus @classmethod - def initialize(cls, sim_context: "SimulationContext") -> None: + def initialize(cls, sim_context: SimulationContext) -> None: """Initialize the physics manager.""" from isaaclab.sim.utils.stage import get_current_stage_id @@ -305,8 +312,12 @@ def raise_callback_exception_if_any(cls) -> None: @classmethod def register_callback( - cls, callback: Callable, event: PhysicsEvent | IsaacEvents, order: int = 0, - name: str | None = None, wrap_weak_ref: bool = True, + cls, + callback: Callable, + event: PhysicsEvent | IsaacEvents, + order: int = 0, + name: str | None = None, + wrap_weak_ref: bool = True, ) -> CallbackHandle: """Register a callback. Accepts both PhysicsEvent and IsaacEvents.""" if isinstance(event, IsaacEvents): @@ -333,10 +344,16 @@ def _subscribe_isaac(cls, callback: Callable, event: IsaacEvents, order: int, na def guarded(cb: Callable) -> Callable: def wrapper(dt: float) -> Any: return cb(dt) if cls._view_created else None + return wrapper - if event in (IsaacEvents.PHYSICS_WARMUP, IsaacEvents.PHYSICS_READY, IsaacEvents.POST_RESET, - IsaacEvents.SIMULATION_VIEW_CREATED, IsaacEvents.PRIM_DELETION): + if event in ( + IsaacEvents.PHYSICS_WARMUP, + IsaacEvents.PHYSICS_READY, + IsaacEvents.POST_RESET, + IsaacEvents.SIMULATION_VIEW_CREATED, + IsaacEvents.PRIM_DELETION, + ): return cls._event_bus.observe_event(event_name=event.value, order=order, on_event=callback) elif event == IsaacEvents.POST_PHYSICS_STEP: return cls._physx.subscribe_physics_on_step_events(guarded(callback), pre_step=False, order=order) @@ -428,8 +445,19 @@ def _configure_physics(cls) -> None: ) # apply remaining cfg attributes to scene - skip = {"solver_type", "enable_ccd", "solve_articulation_contact_last", "dt", "device", - "render_interval", "gravity", "physics_prim_path", "use_fabric", "physics_material", "class_type"} + skip = { + "solver_type", + "enable_ccd", + "solve_articulation_contact_last", + "dt", + "device", + "render_interval", + "gravity", + "physics_prim_path", + "use_fabric", + "physics_material", + "class_type", + } for key, value in cfg.to_dict().items(): # type: ignore if key not in skip: attr_name = "bounce_threshold" if key == "bounce_threshold_velocity" else key @@ -464,6 +492,7 @@ def _load_fabric(cls) -> None: if not ext_mgr.is_extension_enabled("omni.physx.fabric"): ext_mgr.set_extension_enabled_immediate("omni.physx.fabric", True) from omni.physxfabric import get_physx_fabric_interface + cls._fabric = get_physx_fabric_interface() cls._update_fabric = getattr(cls._fabric, "force_update", cls._fabric.update) else: @@ -473,8 +502,13 @@ def _load_fabric(cls) -> None: cls._update_fabric = None # disable usd sync when fabric is enabled - for key in ["updateToUsd", "updateParticlesToUsd", "updateVelocitiesToUsd", - "updateForceSensorsToUsd", "updateResidualsToUsd"]: + for key in [ + "updateToUsd", + "updateParticlesToUsd", + "updateVelocitiesToUsd", + "updateForceSensorsToUsd", + "updateResidualsToUsd", + ]: settings.set_bool(f"/physics/{key}", not use_fabric) settings.set_bool("/isaaclab/fabric_enabled", use_fabric) settings.set_bool("/physics/visualizationDisplaySimulationOutput", False) @@ -487,6 +521,7 @@ def _warmup_and_create_views(cls) -> None: # Get stage ID first (needed for both warmup and view creation) from isaaclab.sim.utils.stage import get_current_stage_id + stage_id = get_current_stage_id() # Attach stage to PhysX BEFORE loading/starting - critical for GPU pipeline diff --git a/source/isaaclab_physx/isaaclab_physx/physics/physx_manager_cfg.py b/source/isaaclab_physx/isaaclab_physx/physics/physx_manager_cfg.py index 936c83bd9ce..03507f82d8b 100644 --- a/source/isaaclab_physx/isaaclab_physx/physics/physx_manager_cfg.py +++ b/source/isaaclab_physx/isaaclab_physx/physics/physx_manager_cfg.py @@ -9,8 +9,8 @@ from typing import TYPE_CHECKING, Literal -from isaaclab.utils import configclass from isaaclab.physics import PhysicsManagerCfg +from isaaclab.utils import configclass from .physx_manager import PhysxManager @@ -139,7 +139,8 @@ class PhysxManagerCfg(PhysicsManagerCfg): .. note:: - We recommend setting this flag to true only when the simulation step size is large (i.e., less than 30 Hz or more than 0.0333 seconds). + We recommend setting this flag to true only when the simulation step size is large + (i.e., less than 30 Hz or more than 0.0333 seconds). .. warning:: @@ -149,9 +150,10 @@ class PhysxManagerCfg(PhysicsManagerCfg): enable_external_forces_every_iteration: bool = False """Enable/disable external forces every position iteration in the TGS solver. Default is False. - When using the TGS solver (:attr:`solver_type` is 1), this flag allows enabling external forces every solver position iteration. - This can help improve the accuracy of velocity updates. Consider enabling this flag if the velocities generated by - the simulation are noisy. Increasing the number of velocity iterations, together with this flag, can help improve + When using the TGS solver (:attr:`solver_type` is 1), this flag allows enabling external forces + every solver position iteration. This can help improve the accuracy of velocity updates. + Consider enabling this flag if the velocities generated by the simulation are noisy. + Increasing the number of velocity iterations, together with this flag, can help improve the accuracy of velocity updates. .. note:: diff --git a/source/isaaclab_physx/isaaclab_physx/sensors/contact_sensor/contact_sensor.py b/source/isaaclab_physx/isaaclab_physx/sensors/contact_sensor/contact_sensor.py index c1c37a9f1d4..158a621a360 100644 --- a/source/isaaclab_physx/isaaclab_physx/sensors/contact_sensor/contact_sensor.py +++ b/source/isaaclab_physx/isaaclab_physx/sensors/contact_sensor/contact_sensor.py @@ -15,13 +15,14 @@ import carb import omni.physics.tensors.impl.api as physx -from isaaclab_physx.physics import PhysxManager as SimulationManager from pxr import PhysxSchema import isaaclab.sim as sim_utils from isaaclab.markers import VisualizationMarkers from isaaclab.sensors.contact_sensor import BaseContactSensor +from isaaclab_physx.physics import PhysxManager as SimulationManager + from .contact_sensor_data import ContactSensorData if TYPE_CHECKING: diff --git a/source/isaaclab_physx/isaaclab_physx/sensors/frame_transformer/frame_transformer.py b/source/isaaclab_physx/isaaclab_physx/sensors/frame_transformer/frame_transformer.py index 63f77950c8b..a36955cde2b 100644 --- a/source/isaaclab_physx/isaaclab_physx/sensors/frame_transformer/frame_transformer.py +++ b/source/isaaclab_physx/isaaclab_physx/sensors/frame_transformer/frame_transformer.py @@ -12,7 +12,6 @@ import torch -from isaaclab_physx.physics import PhysxManager as SimulationManager from pxr import UsdPhysics import isaaclab.sim as sim_utils @@ -26,6 +25,8 @@ subtract_frame_transforms, ) +from isaaclab_physx.physics import PhysxManager as SimulationManager + from .frame_transformer_data import FrameTransformerData if TYPE_CHECKING: diff --git a/source/isaaclab_physx/isaaclab_physx/sensors/imu/imu.py b/source/isaaclab_physx/isaaclab_physx/sensors/imu/imu.py index 89593b4f012..6c670767657 100644 --- a/source/isaaclab_physx/isaaclab_physx/sensors/imu/imu.py +++ b/source/isaaclab_physx/isaaclab_physx/sensors/imu/imu.py @@ -10,7 +10,6 @@ import torch -from isaaclab_physx.physics import PhysxManager as SimulationManager from pxr import UsdGeom, UsdPhysics import isaaclab.sim as sim_utils @@ -18,6 +17,8 @@ from isaaclab.markers import VisualizationMarkers from isaaclab.sensors.imu import BaseImu +from isaaclab_physx.physics import PhysxManager as SimulationManager + from .imu_data import ImuData if TYPE_CHECKING: diff --git a/source/isaaclab_physx/isaaclab_physx/visualizers/__init__.py b/source/isaaclab_physx/isaaclab_physx/visualizers/__init__.py index 024a54ab45a..ada27382ed5 100644 --- a/source/isaaclab_physx/isaaclab_physx/visualizers/__init__.py +++ b/source/isaaclab_physx/isaaclab_physx/visualizers/__init__.py @@ -1,3 +1,8 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + # # Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). # # All rights reserved. # # diff --git a/source/isaaclab_physx/isaaclab_physx/visualizers/physx_ov_visualizer.py b/source/isaaclab_physx/isaaclab_physx/visualizers/physx_ov_visualizer.py index 2d62b4d17b6..13ffdfa101b 100644 --- a/source/isaaclab_physx/isaaclab_physx/visualizers/physx_ov_visualizer.py +++ b/source/isaaclab_physx/isaaclab_physx/visualizers/physx_ov_visualizer.py @@ -8,25 +8,29 @@ from __future__ import annotations import enum -import flatdict import logging import os +import weakref +from collections.abc import Callable +from typing import TYPE_CHECKING, Any + +import flatdict import toml import torch -import weakref -from typing import TYPE_CHECKING, Any, Callable import omni.kit.app import omni.timeline + from isaaclab.utils.version import get_isaac_sim_version from isaaclab.visualizers import Visualizer if TYPE_CHECKING: import carb - from .physx_ov_visualizer_cfg import PhysxOVVisualizerCfg from isaaclab.sim.simulation_context import SimulationContext + from .physx_ov_visualizer_cfg import PhysxOVVisualizerCfg + logger = logging.getLogger(__name__) @@ -82,7 +86,7 @@ class TimelineControl: def __init__( self, app_interface: omni.kit.app.IApp, - carb_settings: "carb.settings.ISettings", + carb_settings: carb.settings.ISettings, on_stop_callback: Callable[[], None] | None = None, ): """Initialize timeline control. @@ -223,17 +227,17 @@ class PhysxOVVisualizer(Visualizer): Lifecycle: __init__(cfg) -> initialize(scene_data) -> step() (repeated) -> close() """ - def __init__(self, cfg: "PhysxOVVisualizerCfg"): + def __init__(self, cfg: PhysxOVVisualizerCfg): """Initialize PhysX OV visualizer with configuration. Args: cfg: Configuration for the visualizer. """ super().__init__(cfg) - self.cfg: "PhysxOVVisualizerCfg" = cfg + self.cfg: PhysxOVVisualizerCfg = cfg # Will be set during initialize() - self._sim: "SimulationContext | None" = None + self._sim: SimulationContext | None = None self._app_iface = None self._timeline: TimelineControl | None = None @@ -504,9 +508,7 @@ def set_camera_view( camera_path = self.cfg.camera_prim_path # Use Isaac Sim utility to set camera view - vp_utils.set_camera_view( - eye=list(eye), target=list(target), camera_prim_path=camera_path - ) + vp_utils.set_camera_view(eye=list(eye), target=list(target), camera_prim_path=camera_path) logger.info(f"[PhysxOVVisualizer] Camera set: pos={eye}, target={target}, camera={camera_path}") diff --git a/source/isaaclab_physx/isaaclab_physx/visualizers/physx_ov_visualizer_cfg.py b/source/isaaclab_physx/isaaclab_physx/visualizers/physx_ov_visualizer_cfg.py index 7243118e0e5..0301e201036 100644 --- a/source/isaaclab_physx/isaaclab_physx/visualizers/physx_ov_visualizer_cfg.py +++ b/source/isaaclab_physx/isaaclab_physx/visualizers/physx_ov_visualizer_cfg.py @@ -72,7 +72,7 @@ class PhysxOVVisualizerCfg(VisualizerCfg): window_height: int = 720 """Viewport height in pixels.""" - def create_visualizer(self) -> "PhysxOVVisualizer": + def create_visualizer(self) -> PhysxOVVisualizer: """Create PhysxOVVisualizer instance from this config. Returns: diff --git a/source/isaaclab_physx/test/sensors/check_contact_sensor.py b/source/isaaclab_physx/test/sensors/check_contact_sensor.py index c007c354279..69141d2215a 100644 --- a/source/isaaclab_physx/test/sensors/check_contact_sensor.py +++ b/source/isaaclab_physx/test/sensors/check_contact_sensor.py @@ -35,12 +35,12 @@ """Rest everything follows.""" import torch +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaacsim.core.cloner import GridCloner import isaaclab.sim as sim_utils from isaaclab.assets import Articulation -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sensors.contact_sensor import ContactSensor, ContactSensorCfg from isaaclab.sim import SimulationCfg, SimulationContext from isaaclab.utils.timer import Timer diff --git a/source/isaaclab_physx/test/sensors/test_contact_sensor.py b/source/isaaclab_physx/test/sensors/test_contact_sensor.py index e694fd51f05..1a3e5210a56 100644 --- a/source/isaaclab_physx/test/sensors/test_contact_sensor.py +++ b/source/isaaclab_physx/test/sensors/test_contact_sensor.py @@ -20,6 +20,7 @@ import pytest import torch from flaky import flaky +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg import carb from pxr import PhysxSchema @@ -28,7 +29,6 @@ from isaaclab.assets import RigidObject, RigidObjectCfg from isaaclab.scene import InteractiveScene, InteractiveSceneCfg from isaaclab.sensors import ContactSensor, ContactSensorCfg -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sim import SimulationCfg, SimulationContext, build_simulation_context from isaaclab.sim.utils.stage import get_current_stage from isaaclab.terrains import HfRandomUniformTerrainCfg, TerrainGeneratorCfg, TerrainImporterCfg diff --git a/source/isaaclab_physx/test/sensors/test_frame_transformer.py b/source/isaaclab_physx/test/sensors/test_frame_transformer.py index e077158041e..1253e3cbe0d 100644 --- a/source/isaaclab_physx/test/sensors/test_frame_transformer.py +++ b/source/isaaclab_physx/test/sensors/test_frame_transformer.py @@ -17,11 +17,11 @@ import pytest import scipy.spatial.transform as tf import torch +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg import isaaclab.sim as sim_utils import isaaclab.utils.math as math_utils from isaaclab.assets import RigidObjectCfg -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.scene import InteractiveScene, InteractiveSceneCfg from isaaclab.sensors import FrameTransformerCfg, OffsetCfg from isaaclab.terrains import TerrainImporterCfg @@ -78,7 +78,9 @@ def sim(): # Create a new stage sim_utils.create_new_stage() # Load kit helper - sim = sim_utils.SimulationContext(sim_utils.SimulationCfg(device="cpu", physics_manager_cfg=PhysxManagerCfg(dt=0.005))) + sim = sim_utils.SimulationContext( + sim_utils.SimulationCfg(device="cpu", physics_manager_cfg=PhysxManagerCfg(dt=0.005)) + ) # Set main camera sim.set_camera_view(eye=(5.0, 5.0, 5.0), target=(0.0, 0.0, 0.0)) yield sim diff --git a/source/isaaclab_physx/test/sensors/test_imu.py b/source/isaaclab_physx/test/sensors/test_imu.py index 77bc497a61c..3bb71c6f336 100644 --- a/source/isaaclab_physx/test/sensors/test_imu.py +++ b/source/isaaclab_physx/test/sensors/test_imu.py @@ -17,13 +17,13 @@ import pytest import torch +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg import isaaclab.sim as sim_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_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.scene import InteractiveScene, InteractiveSceneCfg from isaaclab.sensors.imu import Imu, ImuCfg from isaaclab.terrains import TerrainImporterCfg @@ -205,7 +205,9 @@ def setup_sim(): # Create a new stage sim_utils.create_new_stage() # Load simulation context - sim_cfg = sim_utils.SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.001, solver_type=0)) # 0: PGS, 1: TGS --> use PGS for more accurate results + sim_cfg = sim_utils.SimulationCfg( + physics_manager_cfg=PhysxManagerCfg(dt=0.001, solver_type=0) + ) # 0: PGS, 1: TGS --> use PGS for more accurate results sim = sim_utils.SimulationContext(sim_cfg) # construct scene scene_cfg = MySceneCfg(num_envs=2, env_spacing=5.0, lazy_sensor_update=False) diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/allegro_hand/allegro_hand_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/direct/allegro_hand/allegro_hand_env_cfg.py index dc900075d63..12e75257f39 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/allegro_hand/allegro_hand_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/allegro_hand/allegro_hand_env_cfg.py @@ -4,13 +4,14 @@ # SPDX-License-Identifier: BSD-3-Clause +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg + import isaaclab.sim as sim_utils from isaaclab.assets import ArticulationCfg, RigidObjectCfg from isaaclab.envs import DirectRLEnvCfg from isaaclab.markers import VisualizationMarkersCfg from isaaclab.scene import InteractiveSceneCfg from isaaclab.sim import SimulationCfg -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.sim.spawners.materials.physics_materials_cfg import RigidBodyMaterialCfg from isaaclab.utils import configclass from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/ant/ant_env.py b/source/isaaclab_tasks/isaaclab_tasks/direct/ant/ant_env.py index cd509e5d4d3..53fa474502a 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/ant/ant_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/ant/ant_env.py @@ -5,10 +5,11 @@ from __future__ import annotations +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg + import isaaclab.sim as sim_utils from isaaclab.assets import ArticulationCfg from isaaclab.envs import DirectRLEnvCfg -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.scene import InteractiveSceneCfg from isaaclab.sim import SimulationCfg from isaaclab.terrains import TerrainImporterCfg diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/cart_double_pendulum/cart_double_pendulum_env.py b/source/isaaclab_tasks/isaaclab_tasks/direct/cart_double_pendulum/cart_double_pendulum_env.py index b07619f0e6a..68ee6ac9f14 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/cart_double_pendulum/cart_double_pendulum_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/cart_double_pendulum/cart_double_pendulum_env.py @@ -9,11 +9,11 @@ from collections.abc import Sequence import torch +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg import isaaclab.sim as sim_utils from isaaclab.assets import Articulation, ArticulationCfg from isaaclab.envs import DirectMARLEnv, DirectMARLEnvCfg -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.scene import InteractiveSceneCfg from isaaclab.sim import SimulationCfg from isaaclab.sim.spawners.from_files import GroundPlaneCfg, spawn_ground_plane diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/cartpole/cartpole_camera_env.py b/source/isaaclab_tasks/isaaclab_tasks/direct/cartpole/cartpole_camera_env.py index d44877b802e..458df9ee995 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/cartpole/cartpole_camera_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/cartpole/cartpole_camera_env.py @@ -9,11 +9,11 @@ from collections.abc import Sequence import torch +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg import isaaclab.sim as sim_utils from isaaclab.assets import Articulation, ArticulationCfg from isaaclab.envs import DirectRLEnv, DirectRLEnvCfg, ViewerCfg -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.scene import InteractiveSceneCfg from isaaclab.sensors import TiledCamera, TiledCameraCfg, save_images_to_file from isaaclab.sim import SimulationCfg diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/cartpole/cartpole_env.py b/source/isaaclab_tasks/isaaclab_tasks/direct/cartpole/cartpole_env.py index 634b9734175..b5e9db45589 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/cartpole/cartpole_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/cartpole/cartpole_env.py @@ -9,11 +9,11 @@ from collections.abc import Sequence import torch +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg import isaaclab.sim as sim_utils from isaaclab.assets import Articulation, ArticulationCfg from isaaclab.envs import DirectRLEnv, DirectRLEnvCfg -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.scene import InteractiveSceneCfg from isaaclab.sim import SimulationCfg from isaaclab.sim.spawners.from_files import GroundPlaneCfg, spawn_ground_plane diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/humanoid/humanoid_env.py b/source/isaaclab_tasks/isaaclab_tasks/direct/humanoid/humanoid_env.py index 13ad914fdf2..ed5c569b00c 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/humanoid/humanoid_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/humanoid/humanoid_env.py @@ -5,10 +5,11 @@ from __future__ import annotations +from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg + import isaaclab.sim as sim_utils from isaaclab.assets import ArticulationCfg from isaaclab.envs import DirectRLEnvCfg -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.scene import InteractiveSceneCfg from isaaclab.sim import SimulationCfg from isaaclab.terrains import TerrainImporterCfg From 7826c9ab59006edac5854cbfbd07a57493063244 Mon Sep 17 00:00:00 2001 From: Octi Zhang Date: Fri, 6 Feb 2026 18:27:18 -0800 Subject: [PATCH 06/46] update changelog and extension --- source/isaaclab/config/extension.toml | 2 +- source/isaaclab/docs/CHANGELOG.rst | 21 +++++++++++++++++++ source/isaaclab_physx/config/extension.toml | 2 +- source/isaaclab_physx/docs/CHANGELOG.rst | 23 +++++++++++++++++++++ 4 files changed, 46 insertions(+), 2 deletions(-) diff --git a/source/isaaclab/config/extension.toml b/source/isaaclab/config/extension.toml index 2c253461d2b..db6707ba325 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 = "3.0.3" +version = "3.0.4" # Description title = "Isaac Lab framework for Robot Learning" diff --git a/source/isaaclab/docs/CHANGELOG.rst b/source/isaaclab/docs/CHANGELOG.rst index afe9fc0269c..84127cf7612 100644 --- a/source/isaaclab/docs/CHANGELOG.rst +++ b/source/isaaclab/docs/CHANGELOG.rst @@ -1,6 +1,27 @@ Changelog --------- +3.0.4 (2026-02-06) +~~~~~~~~~~~~~~~~~~ + +Changed +^^^^^^^ + +* Refactored :class:`~isaaclab.sim.SimulationContext` to use :class:`~isaaclab.physics.PhysicsManager` + abstraction layer for cleaner separation between simulation orchestration and physics backend. +* Moved physics-specific configuration fields (``dt``, ``gravity``, ``physics_prim_path``, + ``physics_material``, ``use_fabric``) from :class:`~isaaclab.sim.SimulationCfg` to + :class:`~isaaclab_physx.physics.PhysxManagerCfg`. Old API is deprecated but remains functional + with deprecation warnings. + +Deprecated +^^^^^^^^^^ + +* Deprecated passing ``dt``, ``gravity``, ``physics_prim_path``, ``physics_material``, ``use_fabric``, + and ``physx`` directly to :class:`~isaaclab.sim.SimulationCfg`. Use + ``physics_manager_cfg=PhysxManagerCfg(...)`` instead. + + 3.0.3 (2026-02-05) ~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_physx/config/extension.toml b/source/isaaclab_physx/config/extension.toml index 3b43dbb30d8..04f2d6131da 100644 --- a/source/isaaclab_physx/config/extension.toml +++ b/source/isaaclab_physx/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "0.1.4" +version = "0.1.5" # Description title = "PhysX simulation interfaces for IsaacLab core package" diff --git a/source/isaaclab_physx/docs/CHANGELOG.rst b/source/isaaclab_physx/docs/CHANGELOG.rst index 40d9386f2d8..2d984c682af 100644 --- a/source/isaaclab_physx/docs/CHANGELOG.rst +++ b/source/isaaclab_physx/docs/CHANGELOG.rst @@ -1,6 +1,29 @@ Changelog --------- + +0.1.5 (2026-02-06) +~~~~~~~~~~~~~~~~~~ + +Changed +^^^^^^^ + +* Refactored :class:`~isaaclab_physx.physics.PhysxManager` to properly handle physics initialization + order. ``attach_stage()`` is now called before ``start_simulation()`` to ensure GPU buffers are + correctly allocated. +* Removed ``device`` field from :class:`~isaaclab_physx.physics.PhysxManagerCfg`. Device is now + inherited from :attr:`SimulationCfg.device`. + +Added +^^^^^ + +* Added :class:`~isaaclab_physx.physics.PhysxManager` as the concrete PhysX backend implementation + of :class:`~isaaclab.physics.PhysicsManager`. +* Added :class:`~isaaclab_physx.physics.IsaacEvents` enum for PhysX-specific simulation events. +* Added monkey-patching of ``isaacsim.core.simulation_manager.SimulationManager`` in package init + to ensure Isaac Sim uses :class:`~isaaclab_physx.physics.PhysxManager` for callback handling. + + 0.1.4 (2026-02-05) ~~~~~~~~~~~~~~~~~~ From 101ea2787bc11e782d0413cd1c13d0ec3a579a9d Mon Sep 17 00:00:00 2001 From: Octi Zhang Date: Fri, 6 Feb 2026 19:03:14 -0800 Subject: [PATCH 07/46] rename physx ov visualizer to ov visualizer --- .../isaaclab/sim/simulation_context.py | 4 +-- .../isaaclab_physx/visualizers/__init__.py | 19 +++++-------- ...hysx_ov_visualizer.py => ov_visualizer.py} | 28 +++++++++++-------- ...visualizer_cfg.py => ov_visualizer_cfg.py} | 22 +++++++++------ 4 files changed, 38 insertions(+), 35 deletions(-) rename source/isaaclab_physx/isaaclab_physx/visualizers/{physx_ov_visualizer.py => ov_visualizer.py} (97%) rename source/isaaclab_physx/isaaclab_physx/visualizers/{physx_ov_visualizer_cfg.py => ov_visualizer_cfg.py} (81%) diff --git a/source/isaaclab/isaaclab/sim/simulation_context.py b/source/isaaclab/isaaclab/sim/simulation_context.py index 010a1151527..ef6dd6df980 100644 --- a/source/isaaclab/isaaclab/sim/simulation_context.py +++ b/source/isaaclab/isaaclab/sim/simulation_context.py @@ -187,9 +187,9 @@ def _init_visualizers(self) -> None: if len(requested) > 0: # Get or create visualizer configs cfg_list = self.cfg.visualizer_cfgs - from isaaclab_physx.visualizers import PhysxOVVisualizerCfg + from isaaclab_physx.visualizers import OVVisualizerCfg - type_map = {"omniverse": PhysxOVVisualizerCfg} + type_map = {"omniverse": OVVisualizerCfg} viz_cfgs = [] if cfg_list is None: for viz_type in requested: diff --git a/source/isaaclab_physx/isaaclab_physx/visualizers/__init__.py b/source/isaaclab_physx/isaaclab_physx/visualizers/__init__.py index ada27382ed5..74f51e9fc13 100644 --- a/source/isaaclab_physx/isaaclab_physx/visualizers/__init__.py +++ b/source/isaaclab_physx/isaaclab_physx/visualizers/__init__.py @@ -3,19 +3,14 @@ # # SPDX-License-Identifier: BSD-3-Clause -# # Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). -# # All rights reserved. -# # -# # SPDX-License-Identifier: BSD-3-Clause - -# """Sub-package for visualizer configurations and implementations. +"""Sub-package for visualizer configurations and implementations.""" from __future__ import annotations from typing import TYPE_CHECKING # Import config classes (no circular dependency) -from .physx_ov_visualizer_cfg import PhysxOVVisualizerCfg +from .ov_visualizer_cfg import OVVisualizerCfg, PhysxOVVisualizerCfg from isaaclab.visualizers import _VISUALIZER_REGISTRY @@ -23,11 +18,11 @@ from isaaclab.visualizers import Visualizer __all__ = [ - "PhysxOVVisualizerCfg", + "OVVisualizerCfg", + "PhysxOVVisualizerCfg", # Backward compatibility ] -# # Register only selected visualizers to reduce unnecessary imports def get_visualizer_class(name: str) -> type[Visualizer] | None: """Get a visualizer class by name (lazy-loaded). @@ -50,7 +45,7 @@ def get_visualizer_class(name: str) -> type[Visualizer] | None: return _VISUALIZER_REGISTRY[name] if name == "isaacsim_ov": - from .physx_ov_visualizer_cfg import PhysxOVVisualizerCfg + from .ov_visualizer_cfg import OVVisualizerCfg - _VISUALIZER_REGISTRY["isaacsim_ov"] = PhysxOVVisualizerCfg - return PhysxOVVisualizerCfg + _VISUALIZER_REGISTRY["isaacsim_ov"] = OVVisualizerCfg + return OVVisualizerCfg diff --git a/source/isaaclab_physx/isaaclab_physx/visualizers/physx_ov_visualizer.py b/source/isaaclab_physx/isaaclab_physx/visualizers/ov_visualizer.py similarity index 97% rename from source/isaaclab_physx/isaaclab_physx/visualizers/physx_ov_visualizer.py rename to source/isaaclab_physx/isaaclab_physx/visualizers/ov_visualizer.py index 13ffdfa101b..bbb521cc8db 100644 --- a/source/isaaclab_physx/isaaclab_physx/visualizers/physx_ov_visualizer.py +++ b/source/isaaclab_physx/isaaclab_physx/visualizers/ov_visualizer.py @@ -29,7 +29,7 @@ from isaaclab.sim.simulation_context import SimulationContext - from .physx_ov_visualizer_cfg import PhysxOVVisualizerCfg + from .ov_visualizer_cfg import OVVisualizerCfg logger = logging.getLogger(__name__) @@ -213,7 +213,7 @@ def _on_stop_event(self, _) -> None: self._on_stop_callback() -class PhysxOVVisualizer(Visualizer): +class OVVisualizer(Visualizer): """Omniverse visualizer managing viewport/rendering for PhysX workflow. This class extends the base :class:`Visualizer` and handles: @@ -227,14 +227,14 @@ class PhysxOVVisualizer(Visualizer): Lifecycle: __init__(cfg) -> initialize(scene_data) -> step() (repeated) -> close() """ - def __init__(self, cfg: PhysxOVVisualizerCfg): - """Initialize PhysX OV visualizer with configuration. + def __init__(self, cfg: OVVisualizerCfg): + """Initialize OV visualizer with configuration. Args: cfg: Configuration for the visualizer. """ super().__init__(cfg) - self.cfg: PhysxOVVisualizerCfg = cfg + self.cfg: OVVisualizerCfg = cfg # Will be set during initialize() self._sim: SimulationContext | None = None @@ -266,15 +266,15 @@ def initialize(self, scene_data: dict[str, Any] | None = None) -> None: - 'usd_stage': The USD stage (optional, can get from sim context) """ if self._is_initialized: - logger.warning("[PhysxOVVisualizer] Already initialized.") + logger.warning("[OVVisualizer] Already initialized.") return if scene_data is None: - raise ValueError("PhysxOVVisualizer requires scene_data with 'simulation_context'") + raise ValueError("OVVisualizer requires scene_data with 'simulation_context'") self._sim = scene_data.get("simulation_context") if self._sim is None: - raise ValueError("PhysxOVVisualizer requires 'simulation_context' in scene_data") + raise ValueError("OVVisualizer requires 'simulation_context' in scene_data") # Acquire application interface self._app_iface = omni.kit.app.get_app_interface() @@ -345,7 +345,7 @@ def initialize(self, scene_data: dict[str, Any] | None = None) -> None: self.set_camera_view(self.cfg.camera_position, self.cfg.camera_target) self._is_initialized = True - logger.info("[PhysxOVVisualizer] Initialized") + logger.info("[OVVisualizer] Initialized") def step(self, dt: float, state: Any | None = None) -> None: """Update visualization for one step (render the scene). @@ -497,7 +497,7 @@ def set_camera_view( the value from config or "/OmniverseKit_Persp". """ if not self._is_initialized: - logger.warning("[PhysxOVVisualizer] Cannot set camera view - visualizer not initialized.") + logger.warning("[OVVisualizer] Cannot set camera view - visualizer not initialized.") return try: @@ -510,10 +510,10 @@ def set_camera_view( # Use Isaac Sim utility to set camera view vp_utils.set_camera_view(eye=list(eye), target=list(target), camera_prim_path=camera_path) - logger.info(f"[PhysxOVVisualizer] Camera set: pos={eye}, target={target}, camera={camera_path}") + logger.info(f"[OVVisualizer] Camera set: pos={eye}, target={target}, camera={camera_path}") except Exception as e: - logger.warning(f"[PhysxOVVisualizer] Could not set camera: {e}") + logger.warning(f"[OVVisualizer] Could not set camera: {e}") def set_render_mode(self, mode: RenderMode) -> None: """Change the current render mode of the simulation. @@ -759,3 +759,7 @@ def _configure_rendering_dt(self): self._sim.set_setting("/app/runLoops/main/rateLimitEnabled", True) self._sim.set_setting("/app/runLoops/main/rateLimitFrequency", rendering_hz) self._timeline.set_target_framerate(rendering_hz) + + +# Backward compatibility alias +PhysxOVVisualizer = OVVisualizer diff --git a/source/isaaclab_physx/isaaclab_physx/visualizers/physx_ov_visualizer_cfg.py b/source/isaaclab_physx/isaaclab_physx/visualizers/ov_visualizer_cfg.py similarity index 81% rename from source/isaaclab_physx/isaaclab_physx/visualizers/physx_ov_visualizer_cfg.py rename to source/isaaclab_physx/isaaclab_physx/visualizers/ov_visualizer_cfg.py index 0301e201036..a58b643051e 100644 --- a/source/isaaclab_physx/isaaclab_physx/visualizers/physx_ov_visualizer_cfg.py +++ b/source/isaaclab_physx/isaaclab_physx/visualizers/ov_visualizer_cfg.py @@ -12,18 +12,18 @@ from isaaclab.utils import configclass from isaaclab.visualizers import VisualizerCfg -from .physx_ov_visualizer import RenderMode +from .ov_visualizer import RenderMode if TYPE_CHECKING: - from .physx_ov_visualizer import PhysxOVVisualizer + from .ov_visualizer import OVVisualizer @configclass -class PhysxOVVisualizerCfg(VisualizerCfg): +class OVVisualizerCfg(VisualizerCfg): """Configuration for Omniverse visualizer in PhysX-based SimulationContext. This configuration extends :class:`VisualizerCfg` and is used by the - :class:`PhysxOVVisualizer` class which manages viewport/rendering for + :class:`OVVisualizer` class which manages viewport/rendering for PhysX-based SimulationContext workflows. """ @@ -72,12 +72,16 @@ class PhysxOVVisualizerCfg(VisualizerCfg): window_height: int = 720 """Viewport height in pixels.""" - def create_visualizer(self) -> PhysxOVVisualizer: - """Create PhysxOVVisualizer instance from this config. + def create_visualizer(self) -> OVVisualizer: + """Create OVVisualizer instance from this config. Returns: - PhysxOVVisualizer instance configured with this config. + OVVisualizer instance configured with this config. """ - from .physx_ov_visualizer import PhysxOVVisualizer + from .ov_visualizer import OVVisualizer - return PhysxOVVisualizer(self) + return OVVisualizer(self) + + +# Backward compatibility alias +PhysxOVVisualizerCfg = OVVisualizerCfg From ff70cbe710df368a5929de10f6041699704de162 Mon Sep 17 00:00:00 2001 From: Octi Zhang Date: Fri, 6 Feb 2026 20:18:09 -0800 Subject: [PATCH 08/46] bug fixes --- source/isaaclab/isaaclab/sensors/camera/camera.py | 6 +++--- source/isaaclab_tasks/test/env_test_utils.py | 3 +++ 2 files changed, 6 insertions(+), 3 deletions(-) diff --git a/source/isaaclab/isaaclab/sensors/camera/camera.py b/source/isaaclab/isaaclab/sensors/camera/camera.py index 55a669bccc2..bdf3785ea40 100644 --- a/source/isaaclab/isaaclab/sensors/camera/camera.py +++ b/source/isaaclab/isaaclab/sensors/camera/camera.py @@ -125,15 +125,15 @@ def __init__(self, cfg: CameraCfg): carb_settings_iface.set_bool("/isaaclab/render/rtx_sensors", True) # This is only introduced in isaac sim 6.0 - isaac_sim_version = sim_utils.SimulationContext.instance().get_version() - if isaac_sim_version[0] >= 6: + isaac_sim_version = get_isaac_sim_version() + if isaac_sim_version.major >= 6: # Set RTX flag to enable fast path if only depth or albedo is requested supported_fast_types = {"distance_to_camera", "distance_to_image_plane", "depth", "albedo"} if all(data_type in supported_fast_types for data_type in self.cfg.data_types): carb_settings_iface.set_bool("/rtx/sdg/force/disableColorRender", True) # If we have GUI / viewport enabled, we turn off fast path so that the viewport is not black - if sim_utils.SimulationContext.instance().has_gui(): + if carb_settings_iface.get("/isaaclab/has_gui"): carb_settings_iface.set_bool("/rtx/sdg/force/disableColorRender", False) else: if "albedo" in self.cfg.data_types: diff --git a/source/isaaclab_tasks/test/env_test_utils.py b/source/isaaclab_tasks/test/env_test_utils.py index b6f0383abee..6fed4a8b997 100644 --- a/source/isaaclab_tasks/test/env_test_utils.py +++ b/source/isaaclab_tasks/test/env_test_utils.py @@ -16,6 +16,7 @@ import omni.usd from isaaclab.envs.utils.spaces import sample_space +from isaaclab.sim import SimulationContext from isaaclab.utils.version import get_isaac_sim_version from isaaclab_tasks.utils.parse_cfg import parse_env_cfg @@ -216,6 +217,8 @@ def _check_random_actions( else: if hasattr(e, "obj") and hasattr(e.obj, "_is_closed"): e.obj.close() + # Always clear the simulation context singleton to allow next test to run + SimulationContext.clear_instance() pytest.fail(f"Failed to set-up the environment for task {task_name}. Error: {e}") # disable control on stop From 2607065d4df739963c12200ea9f312d2782dd563 Mon Sep 17 00:00:00 2001 From: Octi Zhang Date: Fri, 6 Feb 2026 20:29:38 -0800 Subject: [PATCH 09/46] ensure proper stage clearance --- source/isaaclab_tasks/test/env_test_utils.py | 99 ++++++++++---------- 1 file changed, 48 insertions(+), 51 deletions(-) diff --git a/source/isaaclab_tasks/test/env_test_utils.py b/source/isaaclab_tasks/test/env_test_utils.py index 6fed4a8b997..7ae8fc089c2 100644 --- a/source/isaaclab_tasks/test/env_test_utils.py +++ b/source/isaaclab_tasks/test/env_test_utils.py @@ -190,6 +190,7 @@ def _check_random_actions( # reset the rtx sensors carb setting to False carb.settings.get_settings().set_bool("/isaaclab/render/rtx_sensors", False) + env = None try: # parse config env_cfg = parse_env_cfg(task_name, device=device, num_envs=num_envs) @@ -210,61 +211,57 @@ def _check_random_actions( return env = gym.make(task_name, cfg=env_cfg) - except Exception as e: - # try to close environment on exception - if "env" in locals() and hasattr(env, "_is_closed"): - env.close() - else: - if hasattr(e, "obj") and hasattr(e.obj, "_is_closed"): - e.obj.close() - # Always clear the simulation context singleton to allow next test to run - SimulationContext.clear_instance() - pytest.fail(f"Failed to set-up the environment for task {task_name}. Error: {e}") + # disable control on stop + env.unwrapped.sim._app_control_on_stop_handle = None # type: ignore - # disable control on stop - env.unwrapped.sim._app_control_on_stop_handle = None # type: ignore + # override action space if set to inf for `Isaac-Lift-Teddy-Bear-Franka-IK-Abs-v0` + if task_name == "Isaac-Lift-Teddy-Bear-Franka-IK-Abs-v0": + for i in range(env.unwrapped.single_action_space.shape[0]): + if env.unwrapped.single_action_space.low[i] == float("-inf"): + env.unwrapped.single_action_space.low[i] = -1.0 + if env.unwrapped.single_action_space.high[i] == float("inf"): + env.unwrapped.single_action_space.low[i] = 1.0 - # override action space if set to inf for `Isaac-Lift-Teddy-Bear-Franka-IK-Abs-v0` - if task_name == "Isaac-Lift-Teddy-Bear-Franka-IK-Abs-v0": - for i in range(env.unwrapped.single_action_space.shape[0]): - if env.unwrapped.single_action_space.low[i] == float("-inf"): - env.unwrapped.single_action_space.low[i] = -1.0 - if env.unwrapped.single_action_space.high[i] == float("inf"): - env.unwrapped.single_action_space.low[i] = 1.0 - - # reset environment - obs, _ = env.reset() - - # check signal - assert _check_valid_tensor(obs) - - # simulate environment for num_steps - with torch.inference_mode(): - for _ in range(num_steps): - # sample actions according to the defined space - if multi_agent: - actions = { - agent: sample_space( - env.unwrapped.action_spaces[agent], device=env.unwrapped.device, batch_size=num_envs - ) - for agent in env.unwrapped.possible_agents - } - else: - actions = sample_space( - env.unwrapped.single_action_space, device=env.unwrapped.device, batch_size=num_envs - ) - # apply actions - transition = env.step(actions) - # check signals - for data in transition[:-1]: # exclude info + # reset environment + obs, _ = env.reset() + + # check signal + assert _check_valid_tensor(obs) + + # simulate environment for num_steps + with torch.inference_mode(): + for _ in range(num_steps): + # sample actions according to the defined space if multi_agent: - for agent, agent_data in data.items(): - assert _check_valid_tensor(agent_data), f"Invalid data ('{agent}'): {agent_data}" + actions = { + agent: sample_space( + env.unwrapped.action_spaces[agent], device=env.unwrapped.device, batch_size=num_envs + ) + for agent in env.unwrapped.possible_agents + } else: - assert _check_valid_tensor(data), f"Invalid data: {data}" - - # close environment - env.close() + actions = sample_space( + env.unwrapped.single_action_space, device=env.unwrapped.device, batch_size=num_envs + ) + # apply actions + transition = env.step(actions) + # check signals + for data in transition[:-1]: # exclude info + if multi_agent: + for agent, agent_data in data.items(): + assert _check_valid_tensor(agent_data), f"Invalid data ('{agent}'): {agent_data}" + else: + assert _check_valid_tensor(data), f"Invalid data: {data}" + + finally: + # Always ensure cleanup happens, regardless of success or failure + if env is not None: + try: + env.close() + except Exception: + pass + # Always clear the simulation context singleton to allow next test to run + SimulationContext.clear_instance() def _check_valid_tensor(data: torch.Tensor | dict) -> bool: From b0456038b3f1bd304dfe612dd7d039acc2c0598d Mon Sep 17 00:00:00 2001 From: Octi Zhang Date: Fri, 6 Feb 2026 20:49:24 -0800 Subject: [PATCH 10/46] fix small bugs --- .../isaaclab/sensors/ray_caster/ray_caster.py | 3 +-- .../isaaclab_physx/physics/physx_manager.py | 13 +++++++++++++ 2 files changed, 14 insertions(+), 2 deletions(-) diff --git a/source/isaaclab/isaaclab/sensors/ray_caster/ray_caster.py b/source/isaaclab/isaaclab/sensors/ray_caster/ray_caster.py index bf48c50a447..c082eae559f 100644 --- a/source/isaaclab/isaaclab/sensors/ray_caster/ray_caster.py +++ b/source/isaaclab/isaaclab/sensors/ray_caster/ray_caster.py @@ -20,7 +20,6 @@ import isaaclab.sim as sim_utils import isaaclab.utils.math as math_utils from isaaclab.markers import VisualizationMarkers -from isaaclab.physics import PhysicsManager from isaaclab.sim.views import XformPrimView from isaaclab.terrains.trimesh.utils import make_plane from isaaclab.utils.math import quat_apply, quat_apply_yaw @@ -144,7 +143,7 @@ def _initialize_impl(self): super()._initialize_impl() # obtain global simulation view - self._physics_sim_view = PhysicsManager.get_physics_sim_view() + self._physics_sim_view = sim_utils.SimulationContext.instance().physics_manager.get_physics_sim_view() prim = sim_utils.find_first_matching_prim(self.cfg.prim_path) if prim is None: available_prims = ",".join([str(p.GetPath()) for p in sim_utils.get_current_stage().Traverse()]) diff --git a/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py b/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py index 811f6f3ba3a..8e3cc53309d 100644 --- a/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py +++ b/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py @@ -284,6 +284,11 @@ def close(cls) -> None: def get_physics_sim_view(cls) -> omni.physics.tensors.SimulationView | None: return cls._view + @classmethod + def get_physics_sim_device(cls) -> str: + """Get the physics simulation device (Isaac Sim compatibility alias).""" + return PhysicsManager.get_device() + @classmethod def assets_loading(cls) -> bool: return not cls._assets_loaded @@ -337,6 +342,14 @@ def _subscribe_to_event( isaac_event = _PHYSICS_EVENT_TO_ISAAC_EVENT.get(event) return cls._subscribe_isaac(callback, isaac_event, order, name) if isaac_event else None + @classmethod + def _unsubscribe_from_event( + cls, callback_id: int, event: PhysicsEvent | IsaacEvents, subscription: Any + ) -> None: + """Unsubscribe from PhysX/Isaac events.""" + if subscription is not None and hasattr(subscription, "unsubscribe"): + subscription.unsubscribe() + @classmethod def _subscribe_isaac(cls, callback: Callable, event: IsaacEvents, order: int, name: str | None) -> Any: """Subscribe to an IsaacEvents event.""" From 3204739a606d95ffeac1e716b5edccd02417d686 Mon Sep 17 00:00:00 2001 From: Octi Zhang Date: Fri, 6 Feb 2026 21:36:27 -0800 Subject: [PATCH 11/46] resolve deprecation api calls --- .../isaaclab_physx/visualizers/__init__.py | 5 ++-- .../visualizers/ov_visualizer.py | 3 --- .../visualizers/ov_visualizer_cfg.py | 4 --- .../direct/anymal_c/anymal_c_env_cfg.py | 17 +++++++----- .../direct/automate/assembly_env_cfg.py | 17 ++++++------ .../direct/automate/disassembly_env_cfg.py | 17 ++++++------ .../direct/factory/factory_env_cfg.py | 17 ++++++------ .../franka_cabinet/franka_cabinet_env.py | 17 +++++++----- .../humanoid_amp/humanoid_amp_env_cfg.py | 7 ++--- .../direct/quadcopter/quadcopter_env.py | 17 +++++++----- .../direct/shadow_hand/shadow_hand_env_cfg.py | 27 ++++++++++--------- .../shadow_hand_over_env_cfg.py | 15 ++++++----- .../manager_based/classic/ant/ant_env_cfg.py | 4 +-- .../classic/cartpole/cartpole_env_cfg.py | 2 +- .../classic/humanoid/humanoid_env_cfg.py | 4 +-- .../config/arl_robot_1/no_obstacle_env_cfg.py | 2 +- .../track_position_state_based_env_cfg.py | 6 ++--- .../fixed_base_upper_body_ik_g1_env_cfg.py | 2 +- .../pick_place/locomanipulation_g1_env_cfg.py | 2 +- .../velocity/config/digit/rough_env_cfg.py | 6 ++--- .../velocity/config/spot/flat_env_cfg.py | 12 ++++----- .../locomotion/velocity/velocity_env_cfg.py | 10 +++---- .../manipulation/cabinet/cabinet_env_cfg.py | 7 +++-- .../config/openarm/cabinet_openarm_env_cfg.py | 6 ++--- .../gear_assembly/gear_assembly_env_cfg.py | 7 ++--- .../deploy/reach/reach_env_cfg.py | 2 +- .../manipulation/dexsuite/dexsuite_env_cfg.py | 7 +++-- .../manipulation/inhand/inhand_env_cfg.py | 15 ++++++----- .../config/openarm/lift_openarm_env_cfg.py | 10 +++---- .../manipulation/lift/lift_env_cfg.py | 11 ++++---- .../exhaustpipe_gr1t2_base_env_cfg.py | 2 +- .../pick_place/nutpour_gr1t2_base_env_cfg.py | 2 +- .../pick_place/pickplace_gr1t2_env_cfg.py | 2 +- .../pickplace_gr1t2_waist_enabled_env_cfg.py | 2 +- ...ckplace_unitree_g1_inspire_hand_env_cfg.py | 2 +- .../agibot/place_toy2box_rmp_rel_env_cfg.py | 11 ++++---- .../place_upright_mug_rmp_rel_env_cfg.py | 2 +- .../bimanual/reach_openarm_bi_env_cfg.py | 2 +- .../unimanual/reach_openarm_uni_env_cfg.py | 2 +- .../manipulation/reach/reach_env_cfg.py | 2 +- .../config/galbot/stack_rmp_rel_env_cfg.py | 6 ++--- .../ur10_gripper/stack_joint_pos_env_cfg.py | 2 +- .../manipulation/stack/stack_env_cfg.py | 11 ++++---- .../stack/stack_instance_randomize_env_cfg.py | 11 ++++---- .../config/anymal_c/navigation_env_cfg.py | 6 ++--- 45 files changed, 173 insertions(+), 170 deletions(-) diff --git a/source/isaaclab_physx/isaaclab_physx/visualizers/__init__.py b/source/isaaclab_physx/isaaclab_physx/visualizers/__init__.py index 74f51e9fc13..b5dd5b244aa 100644 --- a/source/isaaclab_physx/isaaclab_physx/visualizers/__init__.py +++ b/source/isaaclab_physx/isaaclab_physx/visualizers/__init__.py @@ -10,7 +10,7 @@ from typing import TYPE_CHECKING # Import config classes (no circular dependency) -from .ov_visualizer_cfg import OVVisualizerCfg, PhysxOVVisualizerCfg +from .ov_visualizer_cfg import OVVisualizerCfg from isaaclab.visualizers import _VISUALIZER_REGISTRY @@ -19,7 +19,6 @@ __all__ = [ "OVVisualizerCfg", - "PhysxOVVisualizerCfg", # Backward compatibility ] @@ -47,5 +46,5 @@ def get_visualizer_class(name: str) -> type[Visualizer] | None: if name == "isaacsim_ov": from .ov_visualizer_cfg import OVVisualizerCfg - _VISUALIZER_REGISTRY["isaacsim_ov"] = OVVisualizerCfg + _VISUALIZER_REGISTRY["omniverse"] = OVVisualizerCfg return OVVisualizerCfg diff --git a/source/isaaclab_physx/isaaclab_physx/visualizers/ov_visualizer.py b/source/isaaclab_physx/isaaclab_physx/visualizers/ov_visualizer.py index bbb521cc8db..91d2ca76fd5 100644 --- a/source/isaaclab_physx/isaaclab_physx/visualizers/ov_visualizer.py +++ b/source/isaaclab_physx/isaaclab_physx/visualizers/ov_visualizer.py @@ -760,6 +760,3 @@ def _configure_rendering_dt(self): self._sim.set_setting("/app/runLoops/main/rateLimitFrequency", rendering_hz) self._timeline.set_target_framerate(rendering_hz) - -# Backward compatibility alias -PhysxOVVisualizer = OVVisualizer diff --git a/source/isaaclab_physx/isaaclab_physx/visualizers/ov_visualizer_cfg.py b/source/isaaclab_physx/isaaclab_physx/visualizers/ov_visualizer_cfg.py index a58b643051e..f32d7590fc0 100644 --- a/source/isaaclab_physx/isaaclab_physx/visualizers/ov_visualizer_cfg.py +++ b/source/isaaclab_physx/isaaclab_physx/visualizers/ov_visualizer_cfg.py @@ -81,7 +81,3 @@ def create_visualizer(self) -> OVVisualizer: from .ov_visualizer import OVVisualizer return OVVisualizer(self) - - -# Backward compatibility alias -PhysxOVVisualizerCfg = OVVisualizerCfg diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/anymal_c/anymal_c_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/direct/anymal_c/anymal_c_env_cfg.py index f5e12b59912..5ceedd3dbcc 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/anymal_c/anymal_c_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/anymal_c/anymal_c_env_cfg.py @@ -14,6 +14,7 @@ from isaaclab.sim import SimulationCfg from isaaclab.terrains import TerrainImporterCfg from isaaclab.utils import configclass +from isaaclab_physx.physics import PhysxManagerCfg ## # Pre-defined configs @@ -61,14 +62,16 @@ class AnymalCFlatEnvCfg(DirectRLEnvCfg): # simulation sim: SimulationCfg = SimulationCfg( - dt=1 / 200, render_interval=decimation, - physics_material=sim_utils.RigidBodyMaterialCfg( - friction_combine_mode="multiply", - restitution_combine_mode="multiply", - static_friction=1.0, - dynamic_friction=1.0, - restitution=0.0, + physics_manager_cfg=PhysxManagerCfg( + dt=1 / 200, + physics_material=sim_utils.RigidBodyMaterialCfg( + friction_combine_mode="multiply", + restitution_combine_mode="multiply", + static_friction=1.0, + dynamic_friction=1.0, + restitution=0.0, + ), ), ) terrain = TerrainImporterCfg( diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/automate/assembly_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/direct/automate/assembly_env_cfg.py index e34068ca377..2edd432c21a 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/automate/assembly_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/automate/assembly_env_cfg.py @@ -8,9 +8,10 @@ from isaaclab.assets import ArticulationCfg from isaaclab.envs import DirectRLEnvCfg from isaaclab.scene import InteractiveSceneCfg -from isaaclab.sim import PhysxCfg, SimulationCfg +from isaaclab.sim import SimulationCfg from isaaclab.sim.spawners.materials.physics_materials_cfg import RigidBodyMaterialCfg from isaaclab.utils import configclass +from isaaclab_physx.physics import PhysxManagerCfg from .assembly_tasks_cfg import ASSET_DIR, Insertion @@ -105,9 +106,9 @@ class AssemblyEnvCfg(DirectRLEnvCfg): episode_length_s = 5.0 sim: SimulationCfg = SimulationCfg( device="cuda:0", - dt=1 / 120, - gravity=(0.0, 0.0, -9.81), - physx=PhysxCfg( + physics_manager_cfg=PhysxManagerCfg( + dt=1 / 120, + gravity=(0.0, 0.0, -9.81), solver_type=1, max_position_iteration_count=192, # Important to avoid interpenetration. max_velocity_iteration_count=1, @@ -117,10 +118,10 @@ class AssemblyEnvCfg(DirectRLEnvCfg): gpu_max_rigid_contact_count=2**23, gpu_max_rigid_patch_count=2**23, gpu_max_num_partitions=1, # Important for stable simulation. - ), - physics_material=RigidBodyMaterialCfg( - static_friction=1.0, - dynamic_friction=1.0, + physics_material=RigidBodyMaterialCfg( + static_friction=1.0, + dynamic_friction=1.0, + ), ), ) diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/automate/disassembly_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/direct/automate/disassembly_env_cfg.py index 9bad1dd388c..8d79ba1df44 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/automate/disassembly_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/automate/disassembly_env_cfg.py @@ -8,9 +8,10 @@ from isaaclab.assets import ArticulationCfg from isaaclab.envs import DirectRLEnvCfg from isaaclab.scene import InteractiveSceneCfg -from isaaclab.sim import PhysxCfg, SimulationCfg +from isaaclab.sim import SimulationCfg from isaaclab.sim.spawners.materials.physics_materials_cfg import RigidBodyMaterialCfg from isaaclab.utils import configclass +from isaaclab_physx.physics import PhysxManagerCfg from .disassembly_tasks_cfg import ASSET_DIR, Extraction @@ -105,9 +106,9 @@ class DisassemblyEnvCfg(DirectRLEnvCfg): episode_length_s = 5.0 sim: SimulationCfg = SimulationCfg( device="cuda:0", - dt=1 / 120, - gravity=(0.0, 0.0, -9.81), - physx=PhysxCfg( + physics_manager_cfg=PhysxManagerCfg( + dt=1 / 120, + gravity=(0.0, 0.0, -9.81), solver_type=1, max_position_iteration_count=192, # Important to avoid interpenetration. max_velocity_iteration_count=1, @@ -117,10 +118,10 @@ class DisassemblyEnvCfg(DirectRLEnvCfg): gpu_max_rigid_contact_count=2**23, gpu_max_rigid_patch_count=2**23, gpu_max_num_partitions=1, # Important for stable simulation. - ), - physics_material=RigidBodyMaterialCfg( - static_friction=1.0, - dynamic_friction=1.0, + physics_material=RigidBodyMaterialCfg( + static_friction=1.0, + dynamic_friction=1.0, + ), ), ) diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/factory/factory_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/direct/factory/factory_env_cfg.py index 8d2f607f18f..ade8b78da73 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/factory/factory_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/factory/factory_env_cfg.py @@ -8,9 +8,10 @@ from isaaclab.assets import ArticulationCfg from isaaclab.envs import DirectRLEnvCfg from isaaclab.scene import InteractiveSceneCfg -from isaaclab.sim import PhysxCfg, SimulationCfg +from isaaclab.sim import SimulationCfg from isaaclab.sim.spawners.materials.physics_materials_cfg import RigidBodyMaterialCfg from isaaclab.utils import configclass +from isaaclab_physx.physics import PhysxManagerCfg from .factory_tasks_cfg import ASSET_DIR, FactoryTask, GearMesh, NutThread, PegInsert @@ -96,9 +97,9 @@ class FactoryEnvCfg(DirectRLEnvCfg): episode_length_s = 10.0 # Probably need to override. sim: SimulationCfg = SimulationCfg( device="cuda:0", - dt=1 / 120, - gravity=(0.0, 0.0, -9.81), - physx=PhysxCfg( + physics_manager_cfg=PhysxManagerCfg( + dt=1 / 120, + gravity=(0.0, 0.0, -9.81), solver_type=1, max_position_iteration_count=192, # Important to avoid interpenetration. max_velocity_iteration_count=1, @@ -109,10 +110,10 @@ class FactoryEnvCfg(DirectRLEnvCfg): gpu_max_rigid_patch_count=2**23, gpu_collision_stack_size=2**28, gpu_max_num_partitions=1, # Important for stable simulation. - ), - physics_material=RigidBodyMaterialCfg( - static_friction=1.0, - dynamic_friction=1.0, + physics_material=RigidBodyMaterialCfg( + static_friction=1.0, + dynamic_friction=1.0, + ), ), ) 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 3ffb4a6a9f2..3c75d7ee407 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 @@ -21,6 +21,7 @@ from isaaclab.utils import configclass from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR, ISAACLAB_NUCLEUS_DIR from isaaclab.utils.math import sample_uniform +from isaaclab_physx.physics import PhysxManagerCfg @configclass @@ -34,14 +35,16 @@ class FrankaCabinetEnvCfg(DirectRLEnvCfg): # simulation sim: SimulationCfg = SimulationCfg( - dt=1 / 120, render_interval=decimation, - physics_material=sim_utils.RigidBodyMaterialCfg( - friction_combine_mode="multiply", - restitution_combine_mode="multiply", - static_friction=1.0, - dynamic_friction=1.0, - restitution=0.0, + physics_manager_cfg=PhysxManagerCfg( + dt=1 / 120, + physics_material=sim_utils.RigidBodyMaterialCfg( + friction_combine_mode="multiply", + restitution_combine_mode="multiply", + static_friction=1.0, + dynamic_friction=1.0, + restitution=0.0, + ), ), ) diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/humanoid_amp/humanoid_amp_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/direct/humanoid_amp/humanoid_amp_env_cfg.py index c7178f746c3..ffc61d976b9 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/humanoid_amp/humanoid_amp_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/humanoid_amp/humanoid_amp_env_cfg.py @@ -12,8 +12,9 @@ from isaaclab.assets import ArticulationCfg from isaaclab.envs import DirectRLEnvCfg from isaaclab.scene import InteractiveSceneCfg -from isaaclab.sim import PhysxCfg, SimulationCfg +from isaaclab.sim import SimulationCfg from isaaclab.utils import configclass +from isaaclab_physx.physics import PhysxManagerCfg from isaaclab_assets import HUMANOID_28_CFG @@ -50,9 +51,9 @@ class HumanoidAmpEnvCfg(DirectRLEnvCfg): # simulation sim: SimulationCfg = SimulationCfg( - dt=1 / 60, render_interval=decimation, - physx=PhysxCfg( + physics_manager_cfg=PhysxManagerCfg( + dt=1 / 60, gpu_found_lost_pairs_capacity=2**23, gpu_total_aggregate_pairs_capacity=2**23, ), diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/quadcopter/quadcopter_env.py b/source/isaaclab_tasks/isaaclab_tasks/direct/quadcopter/quadcopter_env.py index 284ef2845bf..f55c428094c 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/quadcopter/quadcopter_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/quadcopter/quadcopter_env.py @@ -18,6 +18,7 @@ from isaaclab.terrains import TerrainImporterCfg from isaaclab.utils import configclass from isaaclab.utils.math import subtract_frame_transforms +from isaaclab_physx.physics import PhysxManagerCfg ## # Pre-defined configs @@ -60,14 +61,16 @@ class QuadcopterEnvCfg(DirectRLEnvCfg): # simulation sim: SimulationCfg = SimulationCfg( - dt=1 / 100, render_interval=decimation, - physics_material=sim_utils.RigidBodyMaterialCfg( - friction_combine_mode="multiply", - restitution_combine_mode="multiply", - static_friction=1.0, - dynamic_friction=1.0, - restitution=0.0, + physics_manager_cfg=PhysxManagerCfg( + dt=1 / 100, + physics_material=sim_utils.RigidBodyMaterialCfg( + friction_combine_mode="multiply", + restitution_combine_mode="multiply", + static_friction=1.0, + dynamic_friction=1.0, + restitution=0.0, + ), ), ) terrain = TerrainImporterCfg( diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/shadow_hand/shadow_hand_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/direct/shadow_hand/shadow_hand_env_cfg.py index 2bd2d839afa..113e4830d94 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/shadow_hand/shadow_hand_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/shadow_hand/shadow_hand_env_cfg.py @@ -12,11 +12,12 @@ from isaaclab.managers import SceneEntityCfg from isaaclab.markers import VisualizationMarkersCfg from isaaclab.scene import InteractiveSceneCfg -from isaaclab.sim import PhysxCfg, SimulationCfg +from isaaclab.sim import SimulationCfg from isaaclab.sim.spawners.materials.physics_materials_cfg import RigidBodyMaterialCfg from isaaclab.utils import configclass from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR from isaaclab.utils.noise import GaussianNoiseCfg, NoiseModelWithAdditiveBiasCfg +from isaaclab_physx.physics import PhysxManagerCfg from isaaclab_assets.robots.shadow_hand import SHADOW_HAND_CFG @@ -127,13 +128,13 @@ class ShadowHandEnvCfg(DirectRLEnvCfg): # simulation sim: SimulationCfg = SimulationCfg( - dt=1 / 120, render_interval=decimation, - physics_material=RigidBodyMaterialCfg( - static_friction=1.0, - dynamic_friction=1.0, - ), - physx=PhysxCfg( + physics_manager_cfg=PhysxManagerCfg( + dt=1 / 120, + physics_material=RigidBodyMaterialCfg( + static_friction=1.0, + dynamic_friction=1.0, + ), bounce_threshold_velocity=0.2, ), ) @@ -242,13 +243,13 @@ class ShadowHandOpenAIEnvCfg(ShadowHandEnvCfg): obs_type = "openai" # simulation sim: SimulationCfg = SimulationCfg( - dt=1 / 60, render_interval=decimation, - physics_material=RigidBodyMaterialCfg( - static_friction=1.0, - dynamic_friction=1.0, - ), - physx=PhysxCfg( + physics_manager_cfg=PhysxManagerCfg( + dt=1 / 60, + physics_material=RigidBodyMaterialCfg( + static_friction=1.0, + dynamic_friction=1.0, + ), bounce_threshold_velocity=0.2, gpu_max_rigid_contact_count=2**23, gpu_max_rigid_patch_count=2**23, diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/shadow_hand_over/shadow_hand_over_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/direct/shadow_hand_over/shadow_hand_over_env_cfg.py index 78e2d7fa119..be4886a0e35 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/shadow_hand_over/shadow_hand_over_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/shadow_hand_over/shadow_hand_over_env_cfg.py @@ -12,9 +12,10 @@ from isaaclab.managers import SceneEntityCfg from isaaclab.markers import VisualizationMarkersCfg from isaaclab.scene import InteractiveSceneCfg -from isaaclab.sim import PhysxCfg, SimulationCfg +from isaaclab.sim import SimulationCfg from isaaclab.sim.spawners.materials.physics_materials_cfg import RigidBodyMaterialCfg from isaaclab.utils import configclass +from isaaclab_physx.physics import PhysxManagerCfg from isaaclab_assets.robots.shadow_hand import SHADOW_HAND_CFG @@ -124,13 +125,13 @@ class ShadowHandOverEnvCfg(DirectMARLEnvCfg): # simulation sim: SimulationCfg = SimulationCfg( - dt=1 / 120, render_interval=decimation, - physics_material=RigidBodyMaterialCfg( - static_friction=1.0, - dynamic_friction=1.0, - ), - physx=PhysxCfg( + physics_manager_cfg=PhysxManagerCfg( + dt=1 / 120, + physics_material=RigidBodyMaterialCfg( + static_friction=1.0, + dynamic_friction=1.0, + ), bounce_threshold_velocity=0.2, ), ) diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/classic/ant/ant_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/classic/ant/ant_env_cfg.py index 289d4f75f8c..0b3980b2815 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/classic/ant/ant_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/classic/ant/ant_env_cfg.py @@ -175,9 +175,9 @@ def __post_init__(self): self.decimation = 2 self.episode_length_s = 16.0 # simulation settings - self.sim.dt = 1 / 120.0 + self.sim.physics_manager_cfg.dt = 1 / 120.0 self.sim.render_interval = self.decimation - self.sim.physx.bounce_threshold_velocity = 0.2 + self.sim.physics_manager_cfg.bounce_threshold_velocity = 0.2 # default friction material self.sim.physics_material.static_friction = 1.0 self.sim.physics_material.dynamic_friction = 1.0 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/classic/cartpole/cartpole_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/classic/cartpole/cartpole_env_cfg.py index 788920af058..1e72a7d6056 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/classic/cartpole/cartpole_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/classic/cartpole/cartpole_env_cfg.py @@ -177,5 +177,5 @@ def __post_init__(self) -> None: # viewer settings self.viewer.eye = (8.0, 0.0, 5.0) # simulation settings - self.sim.dt = 1 / 120 + self.sim.physics_manager_cfg.dt = 1 / 120 self.sim.render_interval = self.decimation diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/classic/humanoid/humanoid_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/classic/humanoid/humanoid_env_cfg.py index 37b9426df9b..474f5449735 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/classic/humanoid/humanoid_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/classic/humanoid/humanoid_env_cfg.py @@ -212,9 +212,9 @@ def __post_init__(self): self.decimation = 2 self.episode_length_s = 16.0 # simulation settings - self.sim.dt = 1 / 120.0 + self.sim.physics_manager_cfg.dt = 1 / 120.0 self.sim.render_interval = self.decimation - self.sim.physx.bounce_threshold_velocity = 0.2 + self.sim.physics_manager_cfg.bounce_threshold_velocity = 0.2 # default friction material self.sim.physics_material.static_friction = 1.0 self.sim.physics_material.dynamic_friction = 1.0 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/track_position_state_based/config/arl_robot_1/no_obstacle_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/track_position_state_based/config/arl_robot_1/no_obstacle_env_cfg.py index 92a11d82442..59efc3b4ee4 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/track_position_state_based/config/arl_robot_1/no_obstacle_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/track_position_state_based/config/arl_robot_1/no_obstacle_env_cfg.py @@ -21,7 +21,7 @@ def __post_init__(self): super().__post_init__() # switch robot to arl_robot_1 self.scene.robot = ARL_ROBOT_1_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot") - self.scene.robot.actuators["thrusters"].dt = self.sim.dt + self.scene.robot.actuators["thrusters"].dt = self.sim.physics_manager_cfg.dt @configclass diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/track_position_state_based/config/arl_robot_1/track_position_state_based_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/track_position_state_based/config/arl_robot_1/track_position_state_based_env_cfg.py index 238ca65b5ef..bab017bb340 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/track_position_state_based/config/arl_robot_1/track_position_state_based_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/track_position_state_based/config/arl_robot_1/track_position_state_based_env_cfg.py @@ -218,12 +218,12 @@ def __post_init__(self): self.decimation = 10 self.episode_length_s = 5.0 # simulation settings - self.sim.dt = 0.01 + self.sim.physics_manager_cfg.dt = 0.01 self.sim.render_interval = self.decimation - self.sim.physics_material = sim_utils.RigidBodyMaterialCfg( + self.sim.physics_manager_cfg.physics_material = sim_utils.RigidBodyMaterialCfg( friction_combine_mode="multiply", restitution_combine_mode="multiply", static_friction=1.0, dynamic_friction=1.0, ) - self.sim.physx.gpu_max_rigid_patch_count = 10 * 2**15 + self.sim.physics_manager_cfg.gpu_max_rigid_patch_count = 10 * 2**15 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomanipulation/pick_place/fixed_base_upper_body_ik_g1_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomanipulation/pick_place/fixed_base_upper_body_ik_g1_env_cfg.py index d229bca9ab7..bfdb04a77b6 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomanipulation/pick_place/fixed_base_upper_body_ik_g1_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomanipulation/pick_place/fixed_base_upper_body_ik_g1_env_cfg.py @@ -187,7 +187,7 @@ def __post_init__(self): self.decimation = 4 self.episode_length_s = 20.0 # simulation settings - self.sim.dt = 1 / 200 # 200Hz + self.sim.physics_manager_cfg.dt = 1 / 200 # 200Hz self.sim.render_interval = 2 # Set the URDF and mesh paths for the IK controller diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomanipulation/pick_place/locomanipulation_g1_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomanipulation/pick_place/locomanipulation_g1_env_cfg.py index 3c63aea542b..a839e53fce9 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomanipulation/pick_place/locomanipulation_g1_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomanipulation/pick_place/locomanipulation_g1_env_cfg.py @@ -204,7 +204,7 @@ def __post_init__(self): self.decimation = 4 self.episode_length_s = 20.0 # simulation settings - self.sim.dt = 1 / 200 # 200Hz + self.sim.physics_manager_cfg.dt = 1 / 200 # 200Hz self.sim.render_interval = 2 # Set the URDF and mesh paths for the IK controller diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/digit/rough_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/digit/rough_env_cfg.py index 792e6f63947..9d296a1532c 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/digit/rough_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/digit/rough_env_cfg.py @@ -218,14 +218,14 @@ class DigitRoughEnvCfg(LocomotionVelocityRoughEnvCfg): def __post_init__(self): super().__post_init__() self.decimation = 4 - self.sim.dt = 0.005 + self.sim.physics_manager_cfg.dt = 0.005 # Scene self.scene.robot = DIGIT_V4_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot") self.scene.height_scanner.prim_path = "{ENV_REGEX_NS}/Robot/torso_base" self.scene.contact_forces.history_length = self.decimation - self.scene.contact_forces.update_period = self.sim.dt - self.scene.height_scanner.update_period = self.decimation * self.sim.dt + self.scene.contact_forces.update_period = self.sim.physics_manager_cfg.dt + self.scene.height_scanner.update_period = self.decimation * self.sim.physics_manager_cfg.dt # Events: self.events.add_base_mass.params["asset_cfg"] = SceneEntityCfg("robot", body_names="torso_base") diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/spot/flat_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/spot/flat_env_cfg.py index 6bf334e2453..1799d3cec02 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/spot/flat_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/spot/flat_env_cfg.py @@ -318,15 +318,15 @@ def __post_init__(self): self.decimation = 10 # 50 Hz self.episode_length_s = 20.0 # simulation settings - self.sim.dt = 0.002 # 500 Hz + self.sim.physics_manager_cfg.dt = 0.002 # 500 Hz self.sim.render_interval = self.decimation - self.sim.physics_material.static_friction = 1.0 - self.sim.physics_material.dynamic_friction = 1.0 - self.sim.physics_material.friction_combine_mode = "multiply" - self.sim.physics_material.restitution_combine_mode = "multiply" + self.sim.physics_manager_cfg.physics_material.static_friction = 1.0 + self.sim.physics_manager_cfg.physics_material.dynamic_friction = 1.0 + self.sim.physics_manager_cfg.physics_material.friction_combine_mode = "multiply" + self.sim.physics_manager_cfg.physics_material.restitution_combine_mode = "multiply" # update sensor update periods # we tick all the sensors based on the smallest update period (physics update period) - self.scene.contact_forces.update_period = self.sim.dt + self.scene.contact_forces.update_period = self.sim.physics_manager_cfg.dt # switch robot to Spot-d self.scene.robot = SPOT_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot") diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/velocity_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/velocity_env_cfg.py index d7094e77701..ac4043a0dae 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/velocity_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/velocity_env_cfg.py @@ -308,16 +308,16 @@ def __post_init__(self): self.decimation = 4 self.episode_length_s = 20.0 # simulation settings - self.sim.dt = 0.005 + self.sim.physics_manager_cfg.dt = 0.005 self.sim.render_interval = self.decimation - self.sim.physics_material = self.scene.terrain.physics_material - self.sim.physx.gpu_max_rigid_patch_count = 10 * 2**15 + self.sim.physics_manager_cfg.physics_material = self.scene.terrain.physics_material + self.sim.physics_manager_cfg.gpu_max_rigid_patch_count = 10 * 2**15 # update sensor update periods # we tick all the sensors based on the smallest update period (physics update period) if self.scene.height_scanner is not None: - self.scene.height_scanner.update_period = self.decimation * self.sim.dt + self.scene.height_scanner.update_period = self.decimation * self.sim.physics_manager_cfg.dt if self.scene.contact_forces is not None: - self.scene.contact_forces.update_period = self.sim.dt + self.scene.contact_forces.update_period = self.sim.physics_manager_cfg.dt # check if terrain levels curriculum is enabled - if so, enable curriculum for terrain generator # this generates terrains with increasing difficulty and is useful for training diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/cabinet_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/cabinet_env_cfg.py index 6af2c94128f..b40aba8d36a 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/cabinet_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/cabinet_env_cfg.py @@ -271,8 +271,7 @@ def __post_init__(self): self.viewer.eye = (-2.0, 2.0, 2.0) self.viewer.lookat = (0.8, 0.0, 0.5) # simulation settings - self.sim.dt = 1 / 60 # 60Hz + self.sim.physics_manager_cfg.dt = 1 / 60 # 60Hz self.sim.render_interval = self.decimation - self.sim.physx.bounce_threshold_velocity = 0.2 - self.sim.physx.bounce_threshold_velocity = 0.01 - self.sim.physx.friction_correlation_distance = 0.00625 + self.sim.physics_manager_cfg.bounce_threshold_velocity = 0.01 + self.sim.physics_manager_cfg.friction_correlation_distance = 0.00625 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/cabinet_openarm_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/cabinet_openarm_env_cfg.py index 715d83b3ff0..3841f242b4a 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/cabinet_openarm_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/cabinet_openarm_env_cfg.py @@ -276,7 +276,7 @@ def __post_init__(self): self.viewer.eye = (-2.0, 2.0, 2.0) self.viewer.lookat = (0.8, 0.0, 0.5) # simulation settings - self.sim.dt = 1 / 60 # 60Hz + self.sim.physics_manager_cfg.dt = 1 / 60 # 60Hz self.sim.render_interval = self.decimation - self.sim.physx.bounce_threshold_velocity = 0.01 - self.sim.physx.friction_correlation_distance = 0.00625 + self.sim.physics_manager_cfg.bounce_threshold_velocity = 0.01 + self.sim.physics_manager_cfg.friction_correlation_distance = 0.00625 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/deploy/gear_assembly/gear_assembly_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/deploy/gear_assembly/gear_assembly_env_cfg.py index 36adde9d5e8..820b8879011 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/deploy/gear_assembly/gear_assembly_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/deploy/gear_assembly/gear_assembly_env_cfg.py @@ -17,8 +17,9 @@ from isaaclab.managers import SceneEntityCfg from isaaclab.managers import TerminationTermCfg as DoneTerm from isaaclab.scene import InteractiveSceneCfg -from isaaclab.sim.simulation_cfg import PhysxCfg, SimulationCfg +from isaaclab.sim.simulation_cfg import SimulationCfg from isaaclab.utils import configclass +from isaaclab_physx.physics import PhysxManagerCfg from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR from isaaclab.utils.noise import UniformNoiseCfg @@ -301,7 +302,7 @@ class GearAssemblyEnvCfg(ManagerBasedRLEnvCfg): terminations: TerminationsCfg = TerminationsCfg() events: EventCfg = EventCfg() sim: SimulationCfg = SimulationCfg( - physx=PhysxCfg( + physics_manager_cfg=PhysxManagerCfg( # Important to prevent collisionStackSize buffer overflow in contact-rich environments. gpu_collision_stack_size=2**30, gpu_max_rigid_contact_count=2**23, @@ -317,7 +318,7 @@ def __post_init__(self): # simulation settings self.decimation = 4 self.sim.render_interval = self.decimation - self.sim.dt = 1.0 / 120.0 + self.sim.physics_manager_cfg.dt = 1.0 / 120.0 self.gear_offsets = { "gear_small": [0.076125, 0.0, 0.0], diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/deploy/reach/reach_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/deploy/reach/reach_env_cfg.py index 90b65a0f96c..ec7e7baab92 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/deploy/reach/reach_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/deploy/reach/reach_env_cfg.py @@ -212,4 +212,4 @@ def __post_init__(self): self.episode_length_s = 12.0 self.viewer.eye = (3.5, 3.5, 3.5) # simulation settings - self.sim.dt = 1.0 / 120.0 + self.sim.physics_manager_cfg.dt = 1.0 / 120.0 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/dexsuite/dexsuite_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/dexsuite/dexsuite_env_cfg.py index c3a52c71e15..c1d9a76b8f7 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/dexsuite/dexsuite_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/dexsuite/dexsuite_env_cfg.py @@ -423,11 +423,10 @@ def __post_init__(self): self.is_finite_horizon = True # simulation settings - self.sim.dt = 1 / 120 + self.sim.physics_manager_cfg.dt = 1 / 120 self.sim.render_interval = self.decimation - self.sim.physx.bounce_threshold_velocity = 0.2 - self.sim.physx.bounce_threshold_velocity = 0.01 - self.sim.physx.gpu_max_rigid_patch_count = 4 * 5 * 2**15 + self.sim.physics_manager_cfg.bounce_threshold_velocity = 0.01 + self.sim.physics_manager_cfg.gpu_max_rigid_patch_count = 4 * 5 * 2**15 if self.curriculum is not None: self.curriculum.adr.params["pos_tol"] = self.rewards.success.params["pos_std"] / 2 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/inhand/inhand_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/inhand/inhand_env_cfg.py index cf4e1b6ff50..653efb764f4 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/inhand/inhand_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/inhand/inhand_env_cfg.py @@ -17,9 +17,10 @@ from isaaclab.managers import SceneEntityCfg from isaaclab.managers import TerminationTermCfg as DoneTerm from isaaclab.scene import InteractiveSceneCfg -from isaaclab.sim.simulation_cfg import PhysxCfg, SimulationCfg +from isaaclab.sim.simulation_cfg import SimulationCfg from isaaclab.sim.spawners.materials.physics_materials_cfg import RigidBodyMaterialCfg from isaaclab.utils import configclass +from isaaclab_physx.physics import PhysxManagerCfg from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR from isaaclab.utils.noise import AdditiveGaussianNoiseCfg as Gnoise @@ -315,11 +316,11 @@ class InHandObjectEnvCfg(ManagerBasedRLEnvCfg): scene: InHandObjectSceneCfg = InHandObjectSceneCfg(num_envs=8192, env_spacing=0.6) # Simulation settings sim: SimulationCfg = SimulationCfg( - physics_material=RigidBodyMaterialCfg( - static_friction=1.0, - dynamic_friction=1.0, - ), - physx=PhysxCfg( + physics_manager_cfg=PhysxManagerCfg( + physics_material=RigidBodyMaterialCfg( + static_friction=1.0, + dynamic_friction=1.0, + ), bounce_threshold_velocity=0.2, gpu_max_rigid_contact_count=2**20, gpu_max_rigid_patch_count=2**23, @@ -340,7 +341,7 @@ def __post_init__(self): self.decimation = 4 self.episode_length_s = 20.0 # simulation settings - self.sim.dt = 1.0 / 120.0 + self.sim.physics_manager_cfg.dt = 1.0 / 120.0 self.sim.render_interval = self.decimation # change viewer settings self.viewer.eye = (2.0, 2.0, 2.0) diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/lift_openarm_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/lift_openarm_env_cfg.py index 99ac425e0af..46739d3de79 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/lift_openarm_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/lift_openarm_env_cfg.py @@ -233,10 +233,10 @@ def __post_init__(self): self.decimation = 2 self.episode_length_s = 5.0 # simulation settings - self.sim.dt = 0.01 # 100Hz + self.sim.physics_manager_cfg.dt = 0.01 # 100Hz self.sim.render_interval = self.decimation - self.sim.physx.bounce_threshold_velocity = 0.01 - self.sim.physx.gpu_found_lost_aggregate_pairs_capacity = 1024 * 1024 * 4 - self.sim.physx.gpu_total_aggregate_pairs_capacity = 16 * 1024 - self.sim.physx.friction_correlation_distance = 0.00625 + self.sim.physics_manager_cfg.bounce_threshold_velocity = 0.01 + self.sim.physics_manager_cfg.gpu_found_lost_aggregate_pairs_capacity = 1024 * 1024 * 4 + self.sim.physics_manager_cfg.gpu_total_aggregate_pairs_capacity = 16 * 1024 + self.sim.physics_manager_cfg.friction_correlation_distance = 0.00625 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/lift_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/lift_env_cfg.py index a43cc72807b..2d93ca88ce9 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/lift_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/lift_env_cfg.py @@ -214,11 +214,10 @@ def __post_init__(self): self.decimation = 2 self.episode_length_s = 5.0 # simulation settings - self.sim.dt = 0.01 # 100Hz + self.sim.physics_manager_cfg.dt = 0.01 # 100Hz self.sim.render_interval = self.decimation - self.sim.physx.bounce_threshold_velocity = 0.2 - self.sim.physx.bounce_threshold_velocity = 0.01 - self.sim.physx.gpu_found_lost_aggregate_pairs_capacity = 1024 * 1024 * 4 - self.sim.physx.gpu_total_aggregate_pairs_capacity = 16 * 1024 - self.sim.physx.friction_correlation_distance = 0.00625 + self.sim.physics_manager_cfg.bounce_threshold_velocity = 0.01 + self.sim.physics_manager_cfg.gpu_found_lost_aggregate_pairs_capacity = 1024 * 1024 * 4 + self.sim.physics_manager_cfg.gpu_total_aggregate_pairs_capacity = 16 * 1024 + self.sim.physics_manager_cfg.friction_correlation_distance = 0.00625 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/exhaustpipe_gr1t2_base_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/exhaustpipe_gr1t2_base_env_cfg.py index 57c534039e2..cf3e97fb1f2 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/exhaustpipe_gr1t2_base_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/exhaustpipe_gr1t2_base_env_cfg.py @@ -325,7 +325,7 @@ def __post_init__(self): self.decimation = 5 self.episode_length_s = 20.0 # simulation settings - self.sim.dt = 1 / 100 + self.sim.physics_manager_cfg.dt = 1 / 100 self.sim.render_interval = 2 # Set settings for camera rendering diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/nutpour_gr1t2_base_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/nutpour_gr1t2_base_env_cfg.py index 8440dfe4b8c..6709f0a2355 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/nutpour_gr1t2_base_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/nutpour_gr1t2_base_env_cfg.py @@ -360,7 +360,7 @@ def __post_init__(self): self.decimation = 5 self.episode_length_s = 20.0 # simulation settings - self.sim.dt = 1 / 100 + self.sim.physics_manager_cfg.dt = 1 / 100 self.sim.render_interval = 2 # Set settings for camera rendering diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/pickplace_gr1t2_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/pickplace_gr1t2_env_cfg.py index 9e7944d6d1c..26420595270 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/pickplace_gr1t2_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/pickplace_gr1t2_env_cfg.py @@ -377,7 +377,7 @@ def __post_init__(self): self.decimation = 6 self.episode_length_s = 20.0 # simulation settings - self.sim.dt = 1 / 120 # 120Hz + self.sim.physics_manager_cfg.dt = 1 / 120 # 120Hz self.sim.render_interval = 2 # Convert USD to URDF and change revolute joints to fixed diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/pickplace_gr1t2_waist_enabled_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/pickplace_gr1t2_waist_enabled_env_cfg.py index 7bb28650642..6c90d6baf4a 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/pickplace_gr1t2_waist_enabled_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/pickplace_gr1t2_waist_enabled_env_cfg.py @@ -51,7 +51,7 @@ def __post_init__(self): self.decimation = 6 self.episode_length_s = 20.0 # simulation settings - self.sim.dt = 1 / 120 # 120Hz + self.sim.physics_manager_cfg.dt = 1 / 120 # 120Hz self.sim.render_interval = 2 # Add waist joint to pink_ik_cfg diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/pickplace_unitree_g1_inspire_hand_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/pickplace_unitree_g1_inspire_hand_env_cfg.py index 0877c2d3b2a..2d5de66e429 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/pickplace_unitree_g1_inspire_hand_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/pickplace_unitree_g1_inspire_hand_env_cfg.py @@ -368,7 +368,7 @@ def __post_init__(self): self.decimation = 6 self.episode_length_s = 20.0 # simulation settings - self.sim.dt = 1 / 120 # 120Hz + self.sim.physics_manager_cfg.dt = 1 / 120 # 120Hz self.sim.render_interval = 2 # Convert USD to URDF and change revolute joints to fixed diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/place/config/agibot/place_toy2box_rmp_rel_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/place/config/agibot/place_toy2box_rmp_rel_env_cfg.py index 8d2a92c4c87..16b7657c850 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/place/config/agibot/place_toy2box_rmp_rel_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/place/config/agibot/place_toy2box_rmp_rel_env_cfg.py @@ -192,11 +192,10 @@ def __post_init__(self): self.sim.render_interval = self.decimation - self.sim.physx.bounce_threshold_velocity = 0.2 - self.sim.physx.bounce_threshold_velocity = 0.01 - self.sim.physx.gpu_found_lost_aggregate_pairs_capacity = 1024 * 1024 * 4 - self.sim.physx.gpu_total_aggregate_pairs_capacity = 16 * 1024 - self.sim.physx.friction_correlation_distance = 0.00625 + self.sim.physics_manager_cfg.bounce_threshold_velocity = 0.01 + self.sim.physics_manager_cfg.gpu_found_lost_aggregate_pairs_capacity = 1024 * 1024 * 4 + self.sim.physics_manager_cfg.gpu_total_aggregate_pairs_capacity = 16 * 1024 + self.sim.physics_manager_cfg.friction_correlation_distance = 0.00625 # set viewer to see the whole scene self.viewer.eye = [1.5, -1.0, 1.5] @@ -340,7 +339,7 @@ def __post_init__(self): ) # Set the simulation parameters - self.sim.dt = 1 / 60 + self.sim.physics_manager_cfg.dt = 1 / 60 self.sim.render_interval = 6 self.decimation = 3 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/place/config/agibot/place_upright_mug_rmp_rel_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/place/config/agibot/place_upright_mug_rmp_rel_env_cfg.py index 29206a8f486..e0124a58af6 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/place/config/agibot/place_upright_mug_rmp_rel_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/place/config/agibot/place_upright_mug_rmp_rel_env_cfg.py @@ -276,7 +276,7 @@ def __post_init__(self): ) # Set the simulation parameters - self.sim.dt = 1 / 60 + self.sim.physics_manager_cfg.dt = 1 / 60 self.sim.render_interval = 6 self.decimation = 3 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/reach_openarm_bi_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/reach_openarm_bi_env_cfg.py index 7ccdfa0f851..1a00aa98e56 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/reach_openarm_bi_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/reach_openarm_bi_env_cfg.py @@ -332,4 +332,4 @@ def __post_init__(self): self.episode_length_s = 24.0 self.viewer.eye = (3.5, 3.5, 3.5) # simulation settings - self.sim.dt = 1.0 / 60.0 + self.sim.physics_manager_cfg.dt = 1.0 / 60.0 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/reach_openarm_uni_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/reach_openarm_uni_env_cfg.py index 11305e7d1c0..2a533a30795 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/reach_openarm_uni_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/reach_openarm_uni_env_cfg.py @@ -245,4 +245,4 @@ def __post_init__(self): self.episode_length_s = 12.0 self.viewer.eye = (3.5, 3.5, 3.5) # simulation settings - self.sim.dt = 1.0 / 60.0 + self.sim.physics_manager_cfg.dt = 1.0 / 60.0 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/reach_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/reach_env_cfg.py index e1f88e2400c..b7cae39d9c6 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/reach_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/reach_env_cfg.py @@ -209,7 +209,7 @@ def __post_init__(self): self.episode_length_s = 12.0 self.viewer.eye = (3.5, 3.5, 3.5) # simulation settings - self.sim.dt = 1.0 / 60.0 + self.sim.physics_manager_cfg.dt = 1.0 / 60.0 self.teleop_devices = DevicesCfg( devices={ diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/config/galbot/stack_rmp_rel_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/config/galbot/stack_rmp_rel_env_cfg.py index ddc7941414e..e9511fc8024 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/config/galbot/stack_rmp_rel_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/config/galbot/stack_rmp_rel_env_cfg.py @@ -60,7 +60,7 @@ def __post_init__(self): ) # Set the simulation parameters - self.sim.dt = 1 / 60 + self.sim.physics_manager_cfg.dt = 1 / 60 self.sim.render_interval = 6 self.decimation = 3 @@ -126,14 +126,14 @@ def __post_init__(self): use_relative_mode=self.use_relative_mode, ) # Set the simulation parameters - self.sim.dt = 1 / 120 + self.sim.physics_manager_cfg.dt = 1 / 120 self.sim.render_interval = 6 self.decimation = 6 self.episode_length_s = 30.0 # Enable CCD to avoid tunneling - self.sim.physx.enable_ccd = True + self.sim.physics_manager_cfg.enable_ccd = True self.teleop_devices = DevicesCfg( devices={ diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/config/ur10_gripper/stack_joint_pos_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/config/ur10_gripper/stack_joint_pos_env_cfg.py index 296b95e103a..277056daa86 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/config/ur10_gripper/stack_joint_pos_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/config/ur10_gripper/stack_joint_pos_env_cfg.py @@ -132,7 +132,7 @@ def __post_init__(self): self.decimation = 5 self.episode_length_s = 30.0 # simulation settings - self.sim.dt = 0.01 # 100Hz + self.sim.physics_manager_cfg.dt = 0.01 # 100Hz self.sim.render_interval = 5 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/stack_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/stack_env_cfg.py index 238b23c48e5..dcda26f6e54 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/stack_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/stack_env_cfg.py @@ -189,11 +189,10 @@ def __post_init__(self): self.decimation = 5 self.episode_length_s = 30.0 # simulation settings - self.sim.dt = 0.01 # 100Hz + self.sim.physics_manager_cfg.dt = 0.01 # 100Hz self.sim.render_interval = 2 - self.sim.physx.bounce_threshold_velocity = 0.2 - self.sim.physx.bounce_threshold_velocity = 0.01 - self.sim.physx.gpu_found_lost_aggregate_pairs_capacity = 1024 * 1024 * 4 - self.sim.physx.gpu_total_aggregate_pairs_capacity = 16 * 1024 - self.sim.physx.friction_correlation_distance = 0.00625 + self.sim.physics_manager_cfg.bounce_threshold_velocity = 0.01 + self.sim.physics_manager_cfg.gpu_found_lost_aggregate_pairs_capacity = 1024 * 1024 * 4 + self.sim.physics_manager_cfg.gpu_total_aggregate_pairs_capacity = 16 * 1024 + self.sim.physics_manager_cfg.friction_correlation_distance = 0.00625 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/stack_instance_randomize_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/stack_instance_randomize_env_cfg.py index 71b95bfd91d..2ecacf6d129 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/stack_instance_randomize_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/stack_instance_randomize_env_cfg.py @@ -125,11 +125,10 @@ def __post_init__(self): self.decimation = 5 self.episode_length_s = 30.0 # simulation settings - self.sim.dt = 0.01 # 100Hz + self.sim.physics_manager_cfg.dt = 0.01 # 100Hz self.sim.render_interval = self.decimation - self.sim.physx.bounce_threshold_velocity = 0.2 - self.sim.physx.bounce_threshold_velocity = 0.01 - self.sim.physx.gpu_found_lost_aggregate_pairs_capacity = 1024 * 1024 * 4 - self.sim.physx.gpu_total_aggregate_pairs_capacity = 16 * 1024 - self.sim.physx.friction_correlation_distance = 0.00625 + self.sim.physics_manager_cfg.bounce_threshold_velocity = 0.01 + self.sim.physics_manager_cfg.gpu_found_lost_aggregate_pairs_capacity = 1024 * 1024 * 4 + self.sim.physics_manager_cfg.gpu_total_aggregate_pairs_capacity = 16 * 1024 + self.sim.physics_manager_cfg.friction_correlation_distance = 0.00625 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/navigation/config/anymal_c/navigation_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/navigation/config/anymal_c/navigation_env_cfg.py index 96b60705bb5..26a69a3b2d5 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/navigation/config/anymal_c/navigation_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/navigation/config/anymal_c/navigation_env_cfg.py @@ -135,17 +135,17 @@ class NavigationEnvCfg(ManagerBasedRLEnvCfg): def __post_init__(self): """Post initialization.""" - self.sim.dt = LOW_LEVEL_ENV_CFG.sim.dt + self.sim.physics_manager_cfg.dt = LOW_LEVEL_ENV_CFG.sim.physics_manager_cfg.dt self.sim.render_interval = LOW_LEVEL_ENV_CFG.decimation self.decimation = LOW_LEVEL_ENV_CFG.decimation * 10 self.episode_length_s = self.commands.pose_command.resampling_time_range[1] if self.scene.height_scanner is not None: self.scene.height_scanner.update_period = ( - self.actions.pre_trained_policy_action.low_level_decimation * self.sim.dt + self.actions.pre_trained_policy_action.low_level_decimation * self.sim.physics_manager_cfg.dt ) if self.scene.contact_forces is not None: - self.scene.contact_forces.update_period = self.sim.dt + self.scene.contact_forces.update_period = self.sim.physics_manager_cfg.dt class NavigationEnvCfg_PLAY(NavigationEnvCfg): From 5101e4e134dc934bd65db8922ebd8fc93153f517 Mon Sep 17 00:00:00 2001 From: Octi Zhang Date: Fri, 6 Feb 2026 22:19:07 -0800 Subject: [PATCH 12/46] simplified visualizer implementation --- .../isaaclab/envs/manager_based_env.py | 3 - .../isaaclab/managers/event_manager.py | 7 + .../isaaclab/sim/simulation_context.py | 2 + .../isaaclab/isaaclab/visualizers/__init__.py | 43 +- .../isaaclab_physx/physics/physx_manager.py | 15 + .../isaaclab_physx/visualizers/__init__.py | 45 +- .../visualizers/ov_visualizer.py | 671 ++++-------------- .../visualizers/ov_visualizer_cfg.py | 59 +- 8 files changed, 234 insertions(+), 611 deletions(-) diff --git a/source/isaaclab/isaaclab/envs/manager_based_env.py b/source/isaaclab/isaaclab/envs/manager_based_env.py index 7461dd27042..3c41143c7c5 100644 --- a/source/isaaclab/isaaclab/envs/manager_based_env.py +++ b/source/isaaclab/isaaclab/envs/manager_based_env.py @@ -10,9 +10,6 @@ from typing import Any import torch - -import omni.physx - from isaaclab.managers import ActionManager, EventManager, ObservationManager, RecorderManager from isaaclab.scene import InteractiveScene from isaaclab.sim import SimulationContext diff --git a/source/isaaclab/isaaclab/managers/event_manager.py b/source/isaaclab/isaaclab/managers/event_manager.py index 8f92d6859c1..ee49ba0db40 100644 --- a/source/isaaclab/isaaclab/managers/event_manager.py +++ b/source/isaaclab/isaaclab/managers/event_manager.py @@ -191,6 +191,13 @@ def apply( logger.warning(f"Event mode '{mode}' is not defined. Skipping event.") return + # ensure class-based terms are resolved before applying + # the timeline PLAY callback may not have fired yet, so we resolve synchronously + # note: skip for "prestartup" mode as those terms are handled in _prepare_terms + # and scene entities don't exist yet + if mode != "prestartup" and not self._is_scene_entities_resolved: + self._resolve_terms_callback(None) + # check if mode is interval and dt is not provided if mode == "interval" and dt is None: raise ValueError(f"Event mode '{mode}' requires the time-step of the environment.") diff --git a/source/isaaclab/isaaclab/sim/simulation_context.py b/source/isaaclab/isaaclab/sim/simulation_context.py index ef6dd6df980..3801cce25cb 100644 --- a/source/isaaclab/isaaclab/sim/simulation_context.py +++ b/source/isaaclab/isaaclab/sim/simulation_context.py @@ -237,6 +237,8 @@ def reset(self, soft: bool = False) -> None: self.physics_manager.reset(soft) for viz in self._visualizers: viz.reset(soft) + # Start the timeline so the play button is pressed + self.physics_manager.play() self._is_playing = True self._is_stopped = False diff --git a/source/isaaclab/isaaclab/visualizers/__init__.py b/source/isaaclab/isaaclab/visualizers/__init__.py index daa193999c4..79175b3ded2 100644 --- a/source/isaaclab/isaaclab/visualizers/__init__.py +++ b/source/isaaclab/isaaclab/visualizers/__init__.py @@ -1,27 +1,50 @@ -# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# Copyright (c) 2022-2026, The Isaac Lab Project Developers. # All rights reserved. # # SPDX-License-Identifier: BSD-3-Clause -# Visualizer Registry -# ------------------- -# This module uses a registry pattern to decouple visualizer instantiation from specific types. -# Visualizer implementations can register themselves using the `register_visualizer` decorator, -# and configs can create visualizers via the `create_visualizer()` factory method. -# """ +"""Visualizer Registry. -from __future__ import annotations +This module uses a registry pattern to decouple visualizer instantiation +from specific types. Configs can create visualizers via the +`create_visualizer()` factory method. +""" -from typing import Any +from __future__ import annotations # Import base classes first from .visualizer import Visualizer from .visualizer_cfg import VisualizerCfg # Global registry for visualizer types (lazy-loaded) -_VISUALIZER_REGISTRY: dict[str, Any] = {} +_VISUALIZER_REGISTRY: dict[str, type[Visualizer]] = {} + + +def get_visualizer_class(name: str) -> type[Visualizer] | None: + """Get a visualizer class by name (lazy-loaded). + + Args: + name: Visualizer type name (e.g., 'omniverse'). + + Returns: + Visualizer class if found, None otherwise. + """ + # Check if already loaded + if name in _VISUALIZER_REGISTRY: + return _VISUALIZER_REGISTRY[name] + + # Lazy-load visualizer classes from backend packages + if name == "omniverse": + from isaaclab_physx.visualizers import OVVisualizer + + _VISUALIZER_REGISTRY["omniverse"] = OVVisualizer + return OVVisualizer + + return None + __all__ = [ "Visualizer", "VisualizerCfg", + "get_visualizer_class", ] diff --git a/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py b/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py index 8e3cc53309d..080cc036990 100644 --- a/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py +++ b/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py @@ -260,6 +260,21 @@ def step(cls) -> None: cls.raise_callback_exception_if_any() + @classmethod + def play(cls) -> None: + """Start or resume the timeline.""" + cls._timeline.play() + + @classmethod + def pause(cls) -> None: + """Pause the timeline.""" + cls._timeline.pause() + + @classmethod + def stop(cls) -> None: + """Stop the timeline.""" + cls._timeline.stop() + @classmethod def close(cls) -> None: """Clean up physics resources.""" diff --git a/source/isaaclab_physx/isaaclab_physx/visualizers/__init__.py b/source/isaaclab_physx/isaaclab_physx/visualizers/__init__.py index b5dd5b244aa..eb8886841d3 100644 --- a/source/isaaclab_physx/isaaclab_physx/visualizers/__init__.py +++ b/source/isaaclab_physx/isaaclab_physx/visualizers/__init__.py @@ -1,50 +1,15 @@ -# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# Copyright (c) 2022-2026, The Isaac Lab Project Developers. # All rights reserved. # # SPDX-License-Identifier: BSD-3-Clause -"""Sub-package for visualizer configurations and implementations.""" +"""Sub-package for Omniverse visualizer implementations.""" -from __future__ import annotations - -from typing import TYPE_CHECKING - -# Import config classes (no circular dependency) +from .ov_visualizer import OVVisualizer, RenderMode from .ov_visualizer_cfg import OVVisualizerCfg -from isaaclab.visualizers import _VISUALIZER_REGISTRY - -if TYPE_CHECKING: - from isaaclab.visualizers import Visualizer - __all__ = [ + "OVVisualizer", "OVVisualizerCfg", + "RenderMode", ] - - -def get_visualizer_class(name: str) -> type[Visualizer] | None: - """Get a visualizer class by name (lazy-loaded). - - Visualizer classes are imported only when requested to avoid loading - unnecessary dependencies. - - Args: - name: Visualizer type name (e.g., 'newton', 'rerun', 'omniverse'). - - Returns: - Visualizer class if found, None otherwise. - - Example: - >>> visualizer_cls = get_visualizer_class('newton') - >>> if visualizer_cls: - >>> visualizer = visualizer_cls(cfg) - """ - # Check if already loaded - if name in _VISUALIZER_REGISTRY: - return _VISUALIZER_REGISTRY[name] - - if name == "isaacsim_ov": - from .ov_visualizer_cfg import OVVisualizerCfg - - _VISUALIZER_REGISTRY["omniverse"] = OVVisualizerCfg - return OVVisualizerCfg diff --git a/source/isaaclab_physx/isaaclab_physx/visualizers/ov_visualizer.py b/source/isaaclab_physx/isaaclab_physx/visualizers/ov_visualizer.py index 91d2ca76fd5..886fecf2c80 100644 --- a/source/isaaclab_physx/isaaclab_physx/visualizers/ov_visualizer.py +++ b/source/isaaclab_physx/isaaclab_physx/visualizers/ov_visualizer.py @@ -1,230 +1,89 @@ -# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# Copyright (c) 2022-2026, The Isaac Lab Project Developers. # All rights reserved. # # SPDX-License-Identifier: BSD-3-Clause -"""Omniverse visualizer for PhysX-based SimulationContext.""" +"""Omniverse visualizer for Isaac Lab simulation contexts.""" from __future__ import annotations import enum import logging -import os -import weakref -from collections.abc import Callable from typing import TYPE_CHECKING, Any -import flatdict -import toml -import torch - import omni.kit.app -import omni.timeline -from isaaclab.utils.version import get_isaac_sim_version from isaaclab.visualizers import Visualizer -if TYPE_CHECKING: - import carb +from .ov_visualizer_cfg import OVVisualizerCfg +if TYPE_CHECKING: from isaaclab.sim.simulation_context import SimulationContext - from .ov_visualizer_cfg import OVVisualizerCfg - logger = logging.getLogger(__name__) class RenderMode(enum.IntEnum): """Different rendering modes for the simulation. - Render modes correspond to how the viewport and other UI elements (such as listeners to keyboard or mouse - events) are updated. There are three main components that can be updated when the simulation is rendered: - - 1. **UI elements and other extensions**: These are UI elements (such as buttons, sliders, etc.) and other - extensions that are running in the background that need to be updated when the simulation is running. - 2. **Cameras**: These are typically based on Hydra textures and are used to render the scene from different - viewpoints. They can be attached to a viewport or be used independently to render the scene. - 3. **Viewports**: These are windows where you can see the rendered scene. - - Updating each of the above components has a different overhead. For example, updating the viewports is - computationally expensive compared to updating the UI elements. Therefore, it is useful to be able to - control what is updated when the simulation is rendered. This is where the render mode comes in. There are - four different render modes: - - * :attr:`NO_GUI_OR_RENDERING`: The simulation is running without a GUI and off-screen rendering flag is disabled, - so none of the above are updated. - * :attr:`NO_RENDERING`: No rendering, where only 1 is updated at a lower rate. - * :attr:`PARTIAL_RENDERING`: Partial rendering, where only 1 and 2 are updated. - * :attr:`FULL_RENDERING`: Full rendering, where everything (1, 2, 3) is updated. - - .. _Viewports: https://docs.omniverse.nvidia.com/extensions/latest/ext_viewport.html + Render modes correspond to how the viewport and other UI elements + (such as listeners to keyboard or mouse events) are updated. + There are three main components that can be updated when the + simulation is rendered: + + 1. **UI elements and other extensions**: These are UI elements + (such as buttons, sliders, etc.) and other extensions that are + running in the background that need to be updated when the + simulation is running. + 2. **Cameras**: These are typically based on Hydra textures and are + used to render the scene from different viewpoints. They can be + attached to a viewport or be used independently to render the + scene. + 3. **Viewports**: These are windows where you can see the rendered + scene. + + Updating each of the above components has a different overhead. For + example, updating the viewports is computationally expensive + compared to updating the UI elements. Therefore, it is useful to be + able to control what is updated when the simulation is rendered. + This is where the render mode comes in. There are four different + render modes: + + * :attr:`NO_GUI_OR_RENDERING`: The simulation is running without a + GUI and off-screen rendering flag is disabled, so none of the + above are updated. + * :attr:`NO_RENDERING`: No rendering, where only 1 is updated at a + lower rate. + * :attr:`PARTIAL_RENDERING`: Partial rendering, where only 1 and 2 + are updated. + * :attr:`FULL_RENDERING`: Full rendering, where everything (1, 2, + 3) is updated. + + .. _Viewports: https://docs.omniverse.nvidia.com/extensions/latest + /ext_viewport.html """ NO_GUI_OR_RENDERING = -1 - """The simulation is running without a GUI and off-screen rendering is disabled.""" + """The simulation runs without a GUI and off-screen rendering.""" NO_RENDERING = 0 - """No rendering, where only other UI elements are updated at a lower rate.""" + """No rendering, where only other UI elements are updated.""" PARTIAL_RENDERING = 1 - """Partial rendering, where the simulation cameras and UI elements are updated.""" + """Partial rendering, where cameras and UI elements are updated.""" FULL_RENDERING = 2 - """Full rendering, where all the simulation viewports, cameras and UI elements are updated.""" - - -class TimelineControl: - """Helper class for managing timeline lifecycle (play/pause/stop). - - This class wraps the omni.timeline interface and provides a clean API - for controlling simulation playback. It can be composed by visualizers - or simulation contexts that need timeline control. - - Features: - - Play/pause/stop control with proper physics handle propagation - - Stop event callback subscription - - Timeline state queries (is_playing, is_stopped) - """ - - def __init__( - self, - app_interface: omni.kit.app.IApp, - carb_settings: carb.settings.ISettings, - on_stop_callback: Callable[[], None] | None = None, - ): - """Initialize timeline control. - - Args: - app_interface: Omniverse Kit application interface. - carb_settings: Carb settings interface for controlling playSimulations. - on_stop_callback: Optional callback to invoke when simulation stops. - """ - self._app_iface = app_interface - self._carb_settings = carb_settings - self._on_stop_callback = on_stop_callback - - # Acquire timeline interface - self._timeline_iface = omni.timeline.get_timeline_interface() - self._timeline_iface.set_auto_update(True) - - # Setup stop handle callback - self._disable_stop_handle = False - timeline_event_stream = self._timeline_iface.get_timeline_event_stream() - self._stop_handle = timeline_event_stream.create_subscription_to_pop_by_type( - int(omni.timeline.TimelineEventType.STOP), - lambda *args, obj=weakref.proxy(self): obj._on_stop_event(*args), - order=15, - ) - - @property - def timeline_interface(self) -> omni.timeline.ITimeline: - """Get the underlying timeline interface.""" - return self._timeline_iface - - def is_playing(self) -> bool: - """Check whether the simulation is playing. - - Returns: - True if simulation is currently playing, False otherwise. - """ - return self._timeline_iface.is_playing() - - def is_stopped(self) -> bool: - """Check whether the simulation is stopped. - - Returns: - True if simulation is stopped, False otherwise. - """ - return self._timeline_iface.is_stopped() - - def play(self) -> None: - """Start playing the simulation. - - This commits the timeline state and performs one app update step - to propagate all physics handles properly. - """ - self._timeline_iface.play() - self._timeline_iface.commit() - # Perform one step to propagate all physics handles properly - self._carb_settings.set_bool("/app/player/playSimulations", False) - self._app_iface.update() - self._carb_settings.set_bool("/app/player/playSimulations", True) - - def pause(self) -> None: - """Pause the simulation. - - This commits the timeline state to ensure the pause takes effect. - """ - self._timeline_iface.pause() - self._timeline_iface.commit() - - def stop(self) -> None: - """Stop the simulation. - - This commits the timeline state and performs one app update step - to propagate all physics handles properly. - """ - self._timeline_iface.stop() - self._timeline_iface.commit() - # Perform one step to propagate all physics handles properly - self._carb_settings.set_bool("/app/player/playSimulations", False) - self._app_iface.update() - self._carb_settings.set_bool("/app/player/playSimulations", True) - - def set_stop_handle_enabled(self, enabled: bool) -> None: - """Enable or disable the stop handle callback. - - When disabled, the on_stop_callback will not be invoked when - the simulation stops. - - Args: - enabled: If True, the stop handle callback is active. - """ - self._disable_stop_handle = not enabled - - def set_target_framerate(self, hz: int) -> None: - """Set the target framerate for the timeline. - - Args: - hz: Target framerate in Hz. - """ - self._timeline_iface.set_target_framerate(hz) - - def set_time_codes_per_second(self, time_codes_per_second: float) -> None: - """Set the time codes per second for the timeline. - - Args: - time_codes_per_second: Number of time codes per second. - """ - self._timeline_iface.set_time_codes_per_second(time_codes_per_second) - - def close(self) -> None: - """Clean up timeline resources. - - Unsubscribes from the stop event and releases the timeline handle. - """ - if self._stop_handle is not None: - self._stop_handle.unsubscribe() - self._stop_handle = None - - def _on_stop_event(self, _) -> None: - """Internal callback when simulation stops. - - Invokes the on_stop_callback if the stop handle is enabled. - """ - if not self._disable_stop_handle and self._on_stop_callback is not None: - self._on_stop_callback() + """Full rendering, where viewports, cameras and UI are updated.""" class OVVisualizer(Visualizer): - """Omniverse visualizer managing viewport/rendering for PhysX workflow. + """Omniverse visualizer managing viewport/rendering. This class extends the base :class:`Visualizer` and handles: - Viewport context and window management - Render mode switching - Camera view setup - Render settings from configuration - - Throttled rendering for UI responsiveness - - Timeline control (play/pause/stop) - Lifecycle: __init__(cfg) -> initialize(scene_data) -> step() (repeated) -> close() + Lifecycle: + __init__(cfg) -> initialize(scene_data) -> step() -> close() """ def __init__(self, cfg: OVVisualizerCfg): @@ -238,13 +97,10 @@ def __init__(self, cfg: OVVisualizerCfg): # Will be set during initialize() self._sim: SimulationContext | None = None - self._app_iface = None - self._timeline: TimelineControl | None = None + self._app_iface: omni.kit.app.IApp | None = None # Render state - self._local_gui = False - self._livestream_gui = False - self._xr_gui = False + self._has_gui = False self._offscreen_render = False self._render_viewport = False @@ -262,87 +118,74 @@ def initialize(self, scene_data: dict[str, Any] | None = None) -> None: Args: scene_data: Dictionary containing: - - 'simulation_context': The SimulationContext instance (required) - - 'usd_stage': The USD stage (optional, can get from sim context) + - 'simulation_context': SimulationContext instance """ if self._is_initialized: logger.warning("[OVVisualizer] Already initialized.") return if scene_data is None: - raise ValueError("OVVisualizer requires scene_data with 'simulation_context'") + raise ValueError( + "OVVisualizer requires scene_data with 'simulation_context'" + ) self._sim = scene_data.get("simulation_context") if self._sim is None: - raise ValueError("OVVisualizer requires 'simulation_context' in scene_data") + raise ValueError( + "OVVisualizer requires 'simulation_context' in scene_data" + ) # Acquire application interface self._app_iface = omni.kit.app.get_app_interface() - # Detect render flags - self._local_gui = self._sim.carb_settings.get("/app/window/enabled") - self._livestream_gui = self._sim.carb_settings.get("/app/livestream/enabled") - self._xr_gui = self._sim.carb_settings.get("/app/xr/enabled") - self._offscreen_render = bool(self._sim.carb_settings.get("/isaaclab/render/offscreen")) - self._render_viewport = bool(self._sim.carb_settings.get("/isaaclab/render/active_viewport")) - - # Flag for whether any GUI will be rendered (local, livestreamed or viewport) - has_gui = bool(self._local_gui or self._livestream_gui or self._xr_gui) - self._sim.set_setting("/isaaclab/has_gui", has_gui) + # Detect render flags from carb settings + local_gui = self._sim.carb_settings.get("/app/window/enabled") + livestream_gui = self._sim.carb_settings.get( + "/app/livestream/enabled" + ) + xr_gui = self._sim.carb_settings.get("/app/xr/enabled") + self._offscreen_render = bool( + self._sim.carb_settings.get("/isaaclab/render/offscreen") + ) + self._render_viewport = bool( + self._sim.carb_settings.get("/isaaclab/render/active_viewport") + ) - # Apply render settings from config - self._apply_render_settings_from_cfg() + # Flag for whether any GUI will be rendered + self._has_gui = bool(local_gui or livestream_gui or xr_gui) + self._sim.set_setting("/isaaclab/has_gui", self._has_gui) - # Store the default render mode + # Set render mode based on GUI/offscreen settings if self.cfg.default_render_mode is not None: self.render_mode = self.cfg.default_render_mode - elif not has_gui and not self._offscreen_render: - # set default render mode - # note: this is the terminal state: cannot exit from this render mode + elif not self._has_gui and not self._offscreen_render: self.render_mode = RenderMode.NO_GUI_OR_RENDERING - elif not has_gui and self._offscreen_render: - # set default render mode - # note: this is the terminal state: cannot exit from this render mode + elif not self._has_gui and self._offscreen_render: self.render_mode = RenderMode.PARTIAL_RENDERING 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 = RenderMode.FULL_RENDERING - # acquire viewport context self._viewport_context = get_active_viewport() - self._viewport_context.updates_enabled = True # pyright: ignore [reportOptionalMemberAccess] - # acquire viewport window - self._viewport_window = ui.Workspace.get_window(self.cfg.viewport_name or "Viewport") + self._viewport_context.updates_enabled = True + viewport_name = self.cfg.viewport_name or "Viewport" + self._viewport_window = ui.Workspace.get_window(viewport_name) - # 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 + # Disable viewport for offscreen-only rendering 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 - # Override enable scene querying if rendering is enabled - # this is needed for some GUI features - if self._sim.carb_settings.get("/isaaclab/has_gui"): + # Override enable scene querying if GUI is enabled + if self._has_gui: self._sim.cfg.enable_scene_query_support = True - # Initialize timeline control (manages play/pause/stop and stop callbacks) - self._timeline = TimelineControl( - app_interface=self._app_iface, - carb_settings=self._sim.carb_settings, - on_stop_callback=self._on_timeline_stop, - ) - - # Configure rendering/timeline rate - self._configure_rendering_dt() - # Set initial camera view - self.set_camera_view(self.cfg.camera_position, self.cfg.camera_target) + self.set_camera_view( + self.cfg.camera_position, self.cfg.camera_target + ) self._is_initialized = True logger.info("[OVVisualizer] Initialized") @@ -352,7 +195,7 @@ def step(self, dt: float, state: Any | None = None) -> None: Args: dt: Time step in seconds. - state: Updated physics state (unused for OV - USD stage is auto-synced). + state: Updated physics state (unused - USD stage is synced). """ if not self._is_initialized: return @@ -360,42 +203,46 @@ def step(self, dt: float, state: Any | None = None) -> None: self.render() def render(self, mode: RenderMode | None = None) -> None: - """Refreshes the rendering components including UI elements and view-ports depending on the render mode. + """Refreshes rendering components based on the render mode. - This function is used to refresh the rendering components of the simulation. This includes updating the - view-ports, UI elements, and other extensions (besides physics simulation) that are running in the - background. The rendering components are refreshed based on the render mode. + This function is used to refresh the rendering components of + the simulation. This includes updating the view-ports, UI + elements, and other extensions (besides physics simulation) + that are running in the background. The rendering components + are refreshed based on the render mode. - Please see :class:`RenderMode` for more information on the different render modes. + Please see :class:`RenderMode` for more information on the + different render modes. Args: - mode: The rendering mode. Defaults to None, in which case the current rendering mode is used. + mode: The rendering mode. Defaults to None, in which case + the current rendering mode is used. """ if self._sim is None or self._app_iface is None: return - # check if we need to change the render mode + # Check if we need to change the render mode if mode is not None: self.set_render_mode(mode) - # note: we don't call super().render() anymore because they do above operation inside - # and we don't want to do it twice. We may remove it once we drop support for Isaac Sim 2022.2. + + # Update the app (render) self._sim.set_setting("/app/player/playSimulations", False) self._app_iface.update() self._sim.set_setting("/app/player/playSimulations", True) - # app.update() may be changing the cuda device, so we force it back to our desired device here + # app.update() may change the cuda device, so force it back if "cuda" in self._sim.device: + import torch + torch.cuda.set_device(self._sim.device) @property def has_gui(self) -> bool: """Whether any GUI is available (local, livestreamed, or XR).""" - if self._sim is None: - return False - return bool(self._sim.carb_settings.get("/isaaclab/has_gui")) + return self._has_gui @property - def app(self) -> omni.kit.app.IApp: + def app(self) -> omni.kit.app.IApp | None: """Omniverse Kit Application interface.""" return self._app_iface @@ -409,47 +256,25 @@ def render_viewport(self) -> bool: """Whether the default viewport should be rendered.""" return self._render_viewport - # ------------------------------------------------------------------ - # Timeline Control - # ------------------------------------------------------------------ - - @property - def timeline(self) -> TimelineControl | None: - """Get the timeline control instance.""" - return self._timeline - - def is_playing(self) -> bool: - """Check whether the simulation is playing.""" - if self._timeline is None: - return False - return self._timeline.is_playing() + def is_running(self) -> bool: + """Check if visualizer is still running.""" + return self._is_initialized and not self._is_closed def is_stopped(self) -> bool: - """Check whether the visualizer is stopped (closed).""" + """Check if visualizer is stopped (closed).""" return self._is_closed def play(self) -> None: - """Start playing the simulation.""" - if self._timeline is not None: - self._timeline.play() + """Start playing (no-op - timeline managed by SimulationContext).""" + pass def pause(self) -> None: - """Pause the simulation.""" - if self._timeline is not None: - self._timeline.pause() + """Pause (no-op - timeline managed by SimulationContext).""" + pass def stop(self) -> None: - """Stop the simulation.""" - if self._timeline is not None: - self._timeline.stop() - - # ------------------------------------------------------------------ - # Visualizer Interface Implementation - # ------------------------------------------------------------------ - - def is_running(self) -> bool: - """Check if visualizer is still running (independent of pause state).""" - return self._is_initialized and not self._is_closed + """Stop (no-op - timeline managed by SimulationContext).""" + pass def supports_markers(self) -> bool: """Supports markers via USD prims.""" @@ -477,286 +302,92 @@ def _from_frequency(): import omni.kit.loop._loop as omni_loop runner = omni_loop.acquire_loop_interface() - return runner.get_manual_step_size() if runner.get_manual_mode() else _from_frequency() + if runner.get_manual_mode(): + return runner.get_manual_step_size() + return _from_frequency() except Exception: return _from_frequency() def set_camera_view( - self, eye: tuple[float, float, float] | list[float], target: tuple[float, float, float] | list[float] + self, + eye: tuple[float, float, float] | list[float], + target: tuple[float, float, float] | list[float], ) -> None: - """Set the location and target of the viewport camera in the stage. - - Note: - This is a wrapper around the :math:`isaacsim.core.utils.viewports.set_camera_view` function. - It is provided here for convenience to reduce the amount of imports needed. + """Set the location and target of the viewport camera. Args: eye: The location of the camera eye. target: The location of the camera target. - camera_prim_path: The path to the camera primitive in the stage. Defaults to - the value from config or "/OmniverseKit_Persp". """ if not self._is_initialized: - logger.warning("[OVVisualizer] Cannot set camera view - visualizer not initialized.") + logger.warning( + "[OVVisualizer] Cannot set camera - not initialized." + ) return try: - # Import Isaac Sim viewport utilities import isaacsim.core.utils.viewports as vp_utils - # Get the camera prim path - use viewport context or config default camera_path = self.cfg.camera_prim_path - - # Use Isaac Sim utility to set camera view - vp_utils.set_camera_view(eye=list(eye), target=list(target), camera_prim_path=camera_path) - - logger.info(f"[OVVisualizer] Camera set: pos={eye}, target={target}, camera={camera_path}") - + vp_utils.set_camera_view( + eye=list(eye), + target=list(target), + camera_prim_path=camera_path, + ) + logger.info(f"[OVVisualizer] Camera: pos={eye}, target={target}") except Exception as e: logger.warning(f"[OVVisualizer] Could not set camera: {e}") def set_render_mode(self, mode: RenderMode) -> None: """Change the current render mode of the simulation. - Please see :class:`RenderMode` for more information on the different render modes. - - .. note:: - When no GUI is available (locally or livestreamed), we do not need to choose whether the viewport - needs to render or not (since there is no GUI). Thus, in this case, calling the function will not - change the render mode. + Please see :class:`RenderMode` for more information on the + different render modes. Args: - mode: The rendering mode. If different than current rendering mode, - the mode is changed to the new mode. + mode: The rendering mode. Raises: ValueError: If the input mode is not supported. """ - if self._sim is None: - return - - # check if mode change is possible -- not possible when no GUI is available - if not self._sim.carb_settings.get("/isaaclab/has_gui"): + # Check if mode change is possible -- not possible when no GUI + if not self._has_gui: logger.warning( - f"Cannot change render mode when GUI is disabled. Using the default render mode: {self.render_mode}." + f"Cannot change render mode when GUI is disabled. " + f"Using the default render mode: {self.render_mode}." ) return - # check if there is a mode change - # note: this is mostly needed for GUI when we want to switch between full rendering and no rendering. + + # Check if there is a mode change if mode != self.render_mode: if mode == RenderMode.FULL_RENDERING: - # display the viewport and enable updates - self._viewport_context.updates_enabled = True # pyright: ignore [reportOptionalMemberAccess] - self._viewport_window.visible = True # pyright: ignore [reportOptionalMemberAccess] + if self._viewport_context is not None: + self._viewport_context.updates_enabled = True + if self._viewport_window is not None: + self._viewport_window.visible = True elif mode == RenderMode.PARTIAL_RENDERING: - # hide the viewport and disable updates - self._viewport_context.updates_enabled = False # pyright: ignore [reportOptionalMemberAccess] - self._viewport_window.visible = False # pyright: ignore [reportOptionalMemberAccess] + if self._viewport_context is not None: + self._viewport_context.updates_enabled = False + if self._viewport_window is not None: + self._viewport_window.visible = False elif mode == RenderMode.NO_RENDERING: - # hide the viewport and disable updates if self._viewport_context is not None: - self._viewport_context.updates_enabled = False # pyright: ignore [reportOptionalMemberAccess] - self._viewport_window.visible = False # pyright: ignore [reportOptionalMemberAccess] - # reset the throttle counter + self._viewport_context.updates_enabled = False + if self._viewport_window is not None: + self._viewport_window.visible = False self._render_throttle_counter = 0 else: - raise ValueError(f"Unsupported render mode: {mode}! Please check `RenderMode` for details.") - # update render mode + raise ValueError( + f"Unsupported render mode: {mode}! " + "Please check `RenderMode` for details." + ) self.render_mode = mode - def reset(self, soft: bool = False) -> None: - """Reset visualizer (timeline control + warmup renders on hard reset). - - Args: - soft: If True, skip timeline reset and warmup. - """ - if self._timeline is None: - return - - if not soft: - # disable app control on stop handle during reset - self._timeline.set_stop_handle_enabled(False) - if not self.is_stopped(): - self.stop() - self._timeline.set_stop_handle_enabled(True) - # play the simulation - self.play() - # warmup renders to initialize replicator buffers - warmup_count = self.cfg.warmup_renders if hasattr(self.cfg, "warmup_renders") else 2 - for _ in range(warmup_count): - self.render() - def close(self) -> None: """Clean up visualizer resources.""" - # Clean up timeline control - if self._timeline is not None: - self._timeline.close() - self._timeline = None - self._sim = None self._app_iface = None self._viewport_context = None self._viewport_window = None self._is_initialized = False self._is_closed = True - - # ------------------------------------------------------------------ - # Private Methods - # ------------------------------------------------------------------ - - def _on_timeline_stop(self) -> None: - """Callback invoked when the simulation timeline is stopped. - - Once the simulation is stopped, the physics handles go invalid. After that, it is not possible to - resume the simulation from the last state. This leaves the app in an inconsistent state, where - two possible actions can be taken: - - 1. **Keep the app rendering**: In this case, the simulation is kept running and the app is not shutdown. - However, the physics is not updated and the script cannot be resumed from the last state. The - user has to manually close the app to stop the simulation. - 2. **Shutdown the app**: This is the default behavior. In this case, the app is shutdown and - the simulation is stopped. - - Note: - This callback is used only when running the simulation in a standalone python script. In an extension, - it is expected that the user handles the extension shutdown. - """ - # Currently a no-op, but can be extended to handle stop events - pass - - def _apply_render_settings_from_cfg(self): # noqa: C901 - """Sets rtx settings specified in the RenderCfg.""" - if self._sim is None: - return - - # define mapping of user-friendly RenderCfg names to native carb names - rendering_setting_name_mapping = { - "enable_translucency": "/rtx/translucency/enabled", - "enable_reflections": "/rtx/reflections/enabled", - "enable_global_illumination": "/rtx/indirectDiffuse/enabled", - "enable_dlssg": "/rtx-transient/dlssg/enabled", - "enable_dl_denoiser": "/rtx-transient/dldenoiser/enabled", - "dlss_mode": "/rtx/post/dlss/execMode", - "enable_direct_lighting": "/rtx/directLighting/enabled", - "samples_per_pixel": "/rtx/directLighting/sampledLighting/samplesPerPixel", - "enable_shadows": "/rtx/shadows/enabled", - "enable_ambient_occlusion": "/rtx/ambientOcclusion/enabled", - "dome_light_upper_lower_strategy": "/rtx/domeLight/upperLowerStrategy", - } - - not_carb_settings = ["rendering_mode", "carb_settings", "antialiasing_mode"] - - # grab the rendering mode using the following priority: - # 1. command line argument --rendering_mode, if provided - # 2. rendering_mode from Render Config, if set - # 3. lastly, default to "balanced" mode, if neither is specified - rendering_mode = self._sim.carb_settings.get("/isaaclab/rendering/rendering_mode") - if not rendering_mode: - rendering_mode = self._sim.cfg.render.rendering_mode - if not rendering_mode: - rendering_mode = "balanced" - - # set preset settings (same behavior as the CLI arg --rendering_mode) - if rendering_mode is not None: - # check if preset is supported - supported_rendering_modes = ["performance", "balanced", "quality"] - if rendering_mode not in supported_rendering_modes: - raise ValueError( - f"RenderCfg rendering mode '{rendering_mode}' not in supported modes {supported_rendering_modes}." - ) - - # 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 - if get_isaac_sim_version().major < 5: - isaaclab_app_exp_path = os.path.join(isaaclab_app_exp_path, "isaacsim_4_5") - - # grab preset settings - preset_filename = os.path.join(isaaclab_app_exp_path, f"rendering_modes/{rendering_mode}.kit") - with open(preset_filename) as file: - preset_dict = toml.load(file) - preset_dict = dict(flatdict.FlatDict(preset_dict, delimiter=".")) - - # set presets - for key, value in preset_dict.items(): - key = "/" + key.replace(".", "/") # convert to carb setting format - self._sim.set_setting(key, value) - - # set user-friendly named settings - for key, value in vars(self._sim.cfg.render).items(): - if value is None or key in not_carb_settings: - # skip unset settings and non-carb settings - continue - if key not in rendering_setting_name_mapping: - raise ValueError( - f"'{key}' in RenderCfg not found. Note: internal 'rendering_setting_name_mapping' dictionary might" - " need to be updated." - ) - key = rendering_setting_name_mapping[key] - self._sim.set_setting(key, value) - - # set general carb settings - carb_settings = self._sim.cfg.render.carb_settings - if carb_settings is not None: - for key, value in carb_settings.items(): - if "_" in key: - key = "/" + key.replace("_", "/") # convert from python variable style string - elif "." in key: - key = "/" + key.replace(".", "/") # convert from .kit file style string - if self._sim.get_setting(key) is None: - raise ValueError(f"'{key}' in RenderCfg.general_parameters does not map to a carb setting.") - self._sim.set_setting(key, value) - - # set denoiser mode - if self._sim.cfg.render.antialiasing_mode is not None: - try: - import omni.replicator.core as rep - - rep.settings.set_render_rtx_realtime(antialiasing=self._sim.cfg.render.antialiasing_mode) - except Exception: - pass - - # WAR: Ensure /rtx/renderMode RaytracedLighting is correctly cased. - if self._sim.carb_settings.get("/rtx/rendermode").lower() == "raytracedlighting": - self._sim.set_setting("/rtx/rendermode", "RaytracedLighting") - - def _configure_rendering_dt(self): - """Configures the rendering/timeline rate based on physics dt and render interval.""" - if self._sim is None or self._timeline is None: - return - - from pxr import Usd - - cfg = self._sim.cfg - stage = self._sim.stage - # compute rendering frequency - render_interval = max(cfg.render_interval, 1) - rendering_hz = int(1.0 / (cfg.physics_manager_cfg.dt * render_interval)) - - # If rate limiting is enabled, set the rendering rate to the specified value - # Otherwise run the app as fast as possible and do not specify the target rate - if self._sim.get_setting("/app/runLoops/main/rateLimitEnabled"): - self._sim.set_setting("/app/runLoops/main/rateLimitFrequency", rendering_hz) - self._timeline.set_target_framerate(rendering_hz) - - # set stage time codes per second - with Usd.EditContext(stage, stage.GetRootLayer()): - stage.SetTimeCodesPerSecond(rendering_hz) - self._timeline.set_time_codes_per_second(rendering_hz) - - # The isaac sim loop runner is enabled by default in isaac sim apps, - # but in case we are in an app with the kit loop runner, protect against this - try: - import omni.kit.loop._loop as omni_loop - - _loop_runner = omni_loop.acquire_loop_interface() - _loop_runner.set_manual_step_size(cfg.physics_manager_cfg.dt * render_interval) - _loop_runner.set_manual_mode(True) - except Exception: - logger.warning( - "Isaac Sim loop runner not found, enabling rate limiting to support rendering at specified rate" - ) - self._sim.set_setting("/app/runLoops/main/rateLimitEnabled", True) - self._sim.set_setting("/app/runLoops/main/rateLimitFrequency", rendering_hz) - self._timeline.set_target_framerate(rendering_hz) - diff --git a/source/isaaclab_physx/isaaclab_physx/visualizers/ov_visualizer_cfg.py b/source/isaaclab_physx/isaaclab_physx/visualizers/ov_visualizer_cfg.py index f32d7590fc0..878689f7833 100644 --- a/source/isaaclab_physx/isaaclab_physx/visualizers/ov_visualizer_cfg.py +++ b/source/isaaclab_physx/isaaclab_physx/visualizers/ov_visualizer_cfg.py @@ -1,9 +1,9 @@ -# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# Copyright (c) 2022-2026, The Isaac Lab Project Developers. # All rights reserved. # # SPDX-License-Identifier: BSD-3-Clause -"""Configuration for Omniverse visualizer in PhysX-based SimulationContext.""" +"""Configuration for Omniverse-based visualizer.""" from __future__ import annotations @@ -12,50 +12,31 @@ from isaaclab.utils import configclass from isaaclab.visualizers import VisualizerCfg -from .ov_visualizer import RenderMode - if TYPE_CHECKING: - from .ov_visualizer import OVVisualizer + from .ov_visualizer import RenderMode @configclass class OVVisualizerCfg(VisualizerCfg): - """Configuration for Omniverse visualizer in PhysX-based SimulationContext. + """Configuration for Omniverse visualizer using Isaac Sim viewport. - This configuration extends :class:`VisualizerCfg` and is used by the - :class:`OVVisualizer` class which manages viewport/rendering for - PhysX-based SimulationContext workflows. + Displays USD stage, VisualizationMarkers, and LivePlots. + Can attach to existing app or launch standalone. """ visualizer_type: str = "omniverse" """Type identifier for Omniverse visualizer.""" - default_render_mode: RenderMode | None = None - """Default render mode for the visualizer. - - If None, the render mode will be automatically determined based on GUI availability: - - NO_GUI_OR_RENDERING: When no GUI and offscreen rendering is disabled - - PARTIAL_RENDERING: When no GUI but offscreen rendering is enabled - - FULL_RENDERING: When GUI is available (local, livestreamed, or XR) - - See :class:`RenderMode` for available options. - """ - render_throttle_period: int = 5 """Throttle period for rendering updates. - This controls how frequently UI elements are updated when in NO_RENDERING mode. - A higher value means less frequent UI updates, improving performance. + This controls how frequently UI elements are updated when in + NO_RENDERING mode. A higher value means less frequent UI updates, + improving performance. """ - camera_prim_path: str = "/OmniverseKit_Persp" - """Path to the camera primitive in the USD stage.""" - - warmup_renders: int = 2 - """Number of warmup renders to perform on hard reset. - - This is used to initialize replicator buffers before the simulation starts. - """ + default_render_mode: RenderMode | None = None + """Default render mode. If None, auto-detected based on settings.""" viewport_name: str | None = "Viewport" """Viewport name to use. If None, uses active viewport.""" @@ -64,7 +45,10 @@ class OVVisualizerCfg(VisualizerCfg): """Create new viewport with specified name and camera pose.""" dock_position: str = "SAME" - """Dock position for new viewport. Options: 'LEFT', 'RIGHT', 'BOTTOM', 'SAME' (tabs with existing).""" + """Dock position for new viewport. + + Options: 'LEFT', 'RIGHT', 'BOTTOM', 'SAME' (tabs with existing). + """ window_width: int = 1280 """Viewport width in pixels.""" @@ -72,12 +56,11 @@ class OVVisualizerCfg(VisualizerCfg): window_height: int = 720 """Viewport height in pixels.""" - def create_visualizer(self) -> OVVisualizer: - """Create OVVisualizer instance from this config. + camera_prim_path: str = "/OmniverseKit_Persp" + """Path to the camera prim for viewport rendering.""" - Returns: - OVVisualizer instance configured with this config. - """ - from .ov_visualizer import OVVisualizer + camera_position: tuple[float, float, float] = (2.5, 2.5, 2.5) + """Initial camera eye position.""" - return OVVisualizer(self) + camera_target: tuple[float, float, float] = (0.0, 0.0, 0.0) + """Initial camera look-at target.""" From 576d7d7a102fb550e894dfb0dc921476df8b5822 Mon Sep 17 00:00:00 2001 From: Octi Zhang Date: Fri, 6 Feb 2026 22:21:38 -0800 Subject: [PATCH 13/46] clean up --- .../isaaclab/envs/manager_based_env.py | 8 +--- .../isaaclab/isaaclab/visualizers/__init__.py | 5 +++ .../isaaclab_physx/physics/physx_manager.py | 4 +- .../isaaclab_physx/visualizers/__init__.py | 5 +++ .../visualizers/ov_visualizer.py | 41 +++++++------------ .../visualizers/ov_visualizer_cfg.py | 5 +++ .../direct/anymal_c/anymal_c_env_cfg.py | 3 +- .../direct/automate/assembly_env_cfg.py | 3 +- .../direct/automate/disassembly_env_cfg.py | 3 +- .../direct/factory/factory_env_cfg.py | 3 +- .../franka_cabinet/franka_cabinet_env.py | 2 +- .../humanoid_amp/humanoid_amp_env_cfg.py | 3 +- .../direct/quadcopter/quadcopter_env.py | 2 +- .../direct/shadow_hand/shadow_hand_env_cfg.py | 3 +- .../shadow_hand_over_env_cfg.py | 3 +- .../gear_assembly/gear_assembly_env_cfg.py | 3 +- .../manipulation/inhand/inhand_env_cfg.py | 3 +- source/isaaclab_tasks/test/env_test_utils.py | 6 +-- 18 files changed, 53 insertions(+), 52 deletions(-) diff --git a/source/isaaclab/isaaclab/envs/manager_based_env.py b/source/isaaclab/isaaclab/envs/manager_based_env.py index 3c41143c7c5..33128bd4123 100644 --- a/source/isaaclab/isaaclab/envs/manager_based_env.py +++ b/source/isaaclab/isaaclab/envs/manager_based_env.py @@ -10,6 +10,7 @@ from typing import Any import torch + from isaaclab.managers import ActionManager, EventManager, ObservationManager, RecorderManager from isaaclab.scene import InteractiveScene from isaaclab.sim import SimulationContext @@ -17,7 +18,6 @@ from isaaclab.ui.widgets import ManagerLiveVisualizer from isaaclab.utils.seed import configure_seed from isaaclab.utils.timer import Timer -from isaaclab.utils.version import get_isaac_sim_version from .common import VecEnvObs from .manager_based_env_cfg import ManagerBasedEnvCfg @@ -534,12 +534,6 @@ def close(self): del self.scene # clear callbacks and instance - if get_isaac_sim_version().major >= 5: - if self.cfg.sim.create_stage_in_memory: - # detach physx stage - omni.physx.get_physx_simulation_interface().detach_stage() - self.sim.stop() - self.sim.clear_instance() # destroy the window diff --git a/source/isaaclab/isaaclab/visualizers/__init__.py b/source/isaaclab/isaaclab/visualizers/__init__.py index 79175b3ded2..a296ae0233c 100644 --- a/source/isaaclab/isaaclab/visualizers/__init__.py +++ b/source/isaaclab/isaaclab/visualizers/__init__.py @@ -1,3 +1,8 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + # Copyright (c) 2022-2026, The Isaac Lab Project Developers. # All rights reserved. # diff --git a/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py b/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py index 080cc036990..7b966e58891 100644 --- a/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py +++ b/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py @@ -358,9 +358,7 @@ def _subscribe_to_event( return cls._subscribe_isaac(callback, isaac_event, order, name) if isaac_event else None @classmethod - def _unsubscribe_from_event( - cls, callback_id: int, event: PhysicsEvent | IsaacEvents, subscription: Any - ) -> None: + def _unsubscribe_from_event(cls, callback_id: int, event: PhysicsEvent | IsaacEvents, subscription: Any) -> None: """Unsubscribe from PhysX/Isaac events.""" if subscription is not None and hasattr(subscription, "unsubscribe"): subscription.unsubscribe() diff --git a/source/isaaclab_physx/isaaclab_physx/visualizers/__init__.py b/source/isaaclab_physx/isaaclab_physx/visualizers/__init__.py index eb8886841d3..bf63e7d5709 100644 --- a/source/isaaclab_physx/isaaclab_physx/visualizers/__init__.py +++ b/source/isaaclab_physx/isaaclab_physx/visualizers/__init__.py @@ -1,3 +1,8 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + # Copyright (c) 2022-2026, The Isaac Lab Project Developers. # All rights reserved. # diff --git a/source/isaaclab_physx/isaaclab_physx/visualizers/ov_visualizer.py b/source/isaaclab_physx/isaaclab_physx/visualizers/ov_visualizer.py index 886fecf2c80..4be6af38eee 100644 --- a/source/isaaclab_physx/isaaclab_physx/visualizers/ov_visualizer.py +++ b/source/isaaclab_physx/isaaclab_physx/visualizers/ov_visualizer.py @@ -1,3 +1,8 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + # Copyright (c) 2022-2026, The Isaac Lab Project Developers. # All rights reserved. # @@ -125,31 +130,21 @@ def initialize(self, scene_data: dict[str, Any] | None = None) -> None: return if scene_data is None: - raise ValueError( - "OVVisualizer requires scene_data with 'simulation_context'" - ) + raise ValueError("OVVisualizer requires scene_data with 'simulation_context'") self._sim = scene_data.get("simulation_context") if self._sim is None: - raise ValueError( - "OVVisualizer requires 'simulation_context' in scene_data" - ) + raise ValueError("OVVisualizer requires 'simulation_context' in scene_data") # Acquire application interface self._app_iface = omni.kit.app.get_app_interface() # Detect render flags from carb settings local_gui = self._sim.carb_settings.get("/app/window/enabled") - livestream_gui = self._sim.carb_settings.get( - "/app/livestream/enabled" - ) + livestream_gui = self._sim.carb_settings.get("/app/livestream/enabled") xr_gui = self._sim.carb_settings.get("/app/xr/enabled") - self._offscreen_render = bool( - self._sim.carb_settings.get("/isaaclab/render/offscreen") - ) - self._render_viewport = bool( - self._sim.carb_settings.get("/isaaclab/render/active_viewport") - ) + self._offscreen_render = bool(self._sim.carb_settings.get("/isaaclab/render/offscreen")) + self._render_viewport = bool(self._sim.carb_settings.get("/isaaclab/render/active_viewport")) # Flag for whether any GUI will be rendered self._has_gui = bool(local_gui or livestream_gui or xr_gui) @@ -183,9 +178,7 @@ def initialize(self, scene_data: dict[str, Any] | None = None) -> None: self._sim.cfg.enable_scene_query_support = True # Set initial camera view - self.set_camera_view( - self.cfg.camera_position, self.cfg.camera_target - ) + self.set_camera_view(self.cfg.camera_position, self.cfg.camera_target) self._is_initialized = True logger.info("[OVVisualizer] Initialized") @@ -320,9 +313,7 @@ def set_camera_view( target: The location of the camera target. """ if not self._is_initialized: - logger.warning( - "[OVVisualizer] Cannot set camera - not initialized." - ) + logger.warning("[OVVisualizer] Cannot set camera - not initialized.") return try: @@ -353,8 +344,7 @@ def set_render_mode(self, mode: RenderMode) -> None: # Check if mode change is possible -- not possible when no GUI if not self._has_gui: logger.warning( - f"Cannot change render mode when GUI is disabled. " - f"Using the default render mode: {self.render_mode}." + f"Cannot change render mode when GUI is disabled. Using the default render mode: {self.render_mode}." ) return @@ -377,10 +367,7 @@ def set_render_mode(self, mode: RenderMode) -> None: self._viewport_window.visible = False self._render_throttle_counter = 0 else: - raise ValueError( - f"Unsupported render mode: {mode}! " - "Please check `RenderMode` for details." - ) + raise ValueError(f"Unsupported render mode: {mode}! Please check `RenderMode` for details.") self.render_mode = mode def close(self) -> None: diff --git a/source/isaaclab_physx/isaaclab_physx/visualizers/ov_visualizer_cfg.py b/source/isaaclab_physx/isaaclab_physx/visualizers/ov_visualizer_cfg.py index 878689f7833..8e8d4823e65 100644 --- a/source/isaaclab_physx/isaaclab_physx/visualizers/ov_visualizer_cfg.py +++ b/source/isaaclab_physx/isaaclab_physx/visualizers/ov_visualizer_cfg.py @@ -1,3 +1,8 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + # Copyright (c) 2022-2026, The Isaac Lab Project Developers. # All rights reserved. # diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/anymal_c/anymal_c_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/direct/anymal_c/anymal_c_env_cfg.py index 5ceedd3dbcc..089b87e4df7 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/anymal_c/anymal_c_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/anymal_c/anymal_c_env_cfg.py @@ -3,6 +3,8 @@ # # SPDX-License-Identifier: BSD-3-Clause +from isaaclab_physx.physics import PhysxManagerCfg + import isaaclab.envs.mdp as mdp import isaaclab.sim as sim_utils from isaaclab.assets import ArticulationCfg @@ -14,7 +16,6 @@ from isaaclab.sim import SimulationCfg from isaaclab.terrains import TerrainImporterCfg from isaaclab.utils import configclass -from isaaclab_physx.physics import PhysxManagerCfg ## # Pre-defined configs diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/automate/assembly_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/direct/automate/assembly_env_cfg.py index 2edd432c21a..3fe4d7ddaed 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/automate/assembly_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/automate/assembly_env_cfg.py @@ -3,6 +3,8 @@ # # SPDX-License-Identifier: BSD-3-Clause +from isaaclab_physx.physics import PhysxManagerCfg + import isaaclab.sim as sim_utils from isaaclab.actuators import ImplicitActuatorCfg from isaaclab.assets import ArticulationCfg @@ -11,7 +13,6 @@ from isaaclab.sim import SimulationCfg from isaaclab.sim.spawners.materials.physics_materials_cfg import RigidBodyMaterialCfg from isaaclab.utils import configclass -from isaaclab_physx.physics import PhysxManagerCfg from .assembly_tasks_cfg import ASSET_DIR, Insertion diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/automate/disassembly_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/direct/automate/disassembly_env_cfg.py index 8d79ba1df44..e9f0e7164e8 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/automate/disassembly_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/automate/disassembly_env_cfg.py @@ -3,6 +3,8 @@ # # SPDX-License-Identifier: BSD-3-Clause +from isaaclab_physx.physics import PhysxManagerCfg + import isaaclab.sim as sim_utils from isaaclab.actuators import ImplicitActuatorCfg from isaaclab.assets import ArticulationCfg @@ -11,7 +13,6 @@ from isaaclab.sim import SimulationCfg from isaaclab.sim.spawners.materials.physics_materials_cfg import RigidBodyMaterialCfg from isaaclab.utils import configclass -from isaaclab_physx.physics import PhysxManagerCfg from .disassembly_tasks_cfg import ASSET_DIR, Extraction diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/factory/factory_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/direct/factory/factory_env_cfg.py index ade8b78da73..0ec12ed5be8 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/factory/factory_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/factory/factory_env_cfg.py @@ -3,6 +3,8 @@ # # SPDX-License-Identifier: BSD-3-Clause +from isaaclab_physx.physics import PhysxManagerCfg + import isaaclab.sim as sim_utils from isaaclab.actuators import ImplicitActuatorCfg from isaaclab.assets import ArticulationCfg @@ -11,7 +13,6 @@ from isaaclab.sim import SimulationCfg from isaaclab.sim.spawners.materials.physics_materials_cfg import RigidBodyMaterialCfg from isaaclab.utils import configclass -from isaaclab_physx.physics import PhysxManagerCfg from .factory_tasks_cfg import ASSET_DIR, FactoryTask, GearMesh, NutThread, PegInsert 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 3c75d7ee407..0e2a60ccbdf 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 @@ -6,6 +6,7 @@ from __future__ import annotations import torch +from isaaclab_physx.physics import PhysxManagerCfg from isaacsim.core.utils.torch.transformations import tf_combine, tf_inverse, tf_vector from pxr import UsdGeom @@ -21,7 +22,6 @@ from isaaclab.utils import configclass from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR, ISAACLAB_NUCLEUS_DIR from isaaclab.utils.math import sample_uniform -from isaaclab_physx.physics import PhysxManagerCfg @configclass diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/humanoid_amp/humanoid_amp_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/direct/humanoid_amp/humanoid_amp_env_cfg.py index ffc61d976b9..4c80654c0fe 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/humanoid_amp/humanoid_amp_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/humanoid_amp/humanoid_amp_env_cfg.py @@ -8,13 +8,14 @@ import os from dataclasses import MISSING +from isaaclab_physx.physics import PhysxManagerCfg + from isaaclab.actuators import ImplicitActuatorCfg from isaaclab.assets import ArticulationCfg from isaaclab.envs import DirectRLEnvCfg from isaaclab.scene import InteractiveSceneCfg from isaaclab.sim import SimulationCfg from isaaclab.utils import configclass -from isaaclab_physx.physics import PhysxManagerCfg from isaaclab_assets import HUMANOID_28_CFG diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/quadcopter/quadcopter_env.py b/source/isaaclab_tasks/isaaclab_tasks/direct/quadcopter/quadcopter_env.py index f55c428094c..8f536b1b04f 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/quadcopter/quadcopter_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/quadcopter/quadcopter_env.py @@ -7,6 +7,7 @@ import gymnasium as gym import torch +from isaaclab_physx.physics import PhysxManagerCfg import isaaclab.sim as sim_utils from isaaclab.assets import Articulation, ArticulationCfg @@ -18,7 +19,6 @@ from isaaclab.terrains import TerrainImporterCfg from isaaclab.utils import configclass from isaaclab.utils.math import subtract_frame_transforms -from isaaclab_physx.physics import PhysxManagerCfg ## # Pre-defined configs diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/shadow_hand/shadow_hand_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/direct/shadow_hand/shadow_hand_env_cfg.py index 113e4830d94..48328217dbc 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/shadow_hand/shadow_hand_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/shadow_hand/shadow_hand_env_cfg.py @@ -4,6 +4,8 @@ # SPDX-License-Identifier: BSD-3-Clause +from isaaclab_physx.physics import PhysxManagerCfg + import isaaclab.envs.mdp as mdp import isaaclab.sim as sim_utils from isaaclab.assets import ArticulationCfg, RigidObjectCfg @@ -17,7 +19,6 @@ from isaaclab.utils import configclass from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR from isaaclab.utils.noise import GaussianNoiseCfg, NoiseModelWithAdditiveBiasCfg -from isaaclab_physx.physics import PhysxManagerCfg from isaaclab_assets.robots.shadow_hand import SHADOW_HAND_CFG diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/shadow_hand_over/shadow_hand_over_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/direct/shadow_hand_over/shadow_hand_over_env_cfg.py index be4886a0e35..35069c75af7 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/shadow_hand_over/shadow_hand_over_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/shadow_hand_over/shadow_hand_over_env_cfg.py @@ -4,6 +4,8 @@ # SPDX-License-Identifier: BSD-3-Clause +from isaaclab_physx.physics import PhysxManagerCfg + import isaaclab.envs.mdp as mdp import isaaclab.sim as sim_utils from isaaclab.assets import ArticulationCfg, RigidObjectCfg @@ -15,7 +17,6 @@ from isaaclab.sim import SimulationCfg from isaaclab.sim.spawners.materials.physics_materials_cfg import RigidBodyMaterialCfg from isaaclab.utils import configclass -from isaaclab_physx.physics import PhysxManagerCfg from isaaclab_assets.robots.shadow_hand import SHADOW_HAND_CFG diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/deploy/gear_assembly/gear_assembly_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/deploy/gear_assembly/gear_assembly_env_cfg.py index 820b8879011..5f4c00781ed 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/deploy/gear_assembly/gear_assembly_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/deploy/gear_assembly/gear_assembly_env_cfg.py @@ -6,6 +6,8 @@ import os from dataclasses import MISSING +from isaaclab_physx.physics import PhysxManagerCfg + import isaaclab.sim as sim_utils from isaaclab.assets import ArticulationCfg, AssetBaseCfg, RigidObjectCfg from isaaclab.envs import ManagerBasedRLEnvCfg @@ -19,7 +21,6 @@ from isaaclab.scene import InteractiveSceneCfg from isaaclab.sim.simulation_cfg import SimulationCfg from isaaclab.utils import configclass -from isaaclab_physx.physics import PhysxManagerCfg from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR from isaaclab.utils.noise import UniformNoiseCfg diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/inhand/inhand_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/inhand/inhand_env_cfg.py index 653efb764f4..ee20a0dc28f 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/inhand/inhand_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/inhand/inhand_env_cfg.py @@ -7,6 +7,8 @@ from dataclasses import MISSING +from isaaclab_physx.physics import PhysxManagerCfg + import isaaclab.sim as sim_utils from isaaclab.assets import ArticulationCfg, AssetBaseCfg, RigidObjectCfg from isaaclab.envs import ManagerBasedRLEnvCfg @@ -20,7 +22,6 @@ from isaaclab.sim.simulation_cfg import SimulationCfg from isaaclab.sim.spawners.materials.physics_materials_cfg import RigidBodyMaterialCfg from isaaclab.utils import configclass -from isaaclab_physx.physics import PhysxManagerCfg from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR from isaaclab.utils.noise import AdditiveGaussianNoiseCfg as Gnoise diff --git a/source/isaaclab_tasks/test/env_test_utils.py b/source/isaaclab_tasks/test/env_test_utils.py index 7ae8fc089c2..2505a2d973c 100644 --- a/source/isaaclab_tasks/test/env_test_utils.py +++ b/source/isaaclab_tasks/test/env_test_utils.py @@ -256,10 +256,8 @@ def _check_random_actions( finally: # Always ensure cleanup happens, regardless of success or failure if env is not None: - try: - env.close() - except Exception: - pass + env.close() + # Always clear the simulation context singleton to allow next test to run SimulationContext.clear_instance() From 753a29dfd8d8839ef9546bd09a30f11e126a6248 Mon Sep 17 00:00:00 2001 From: Octi Zhang Date: Fri, 6 Feb 2026 22:28:28 -0800 Subject: [PATCH 14/46] pass precommit --- .../isaaclab/isaaclab/visualizers/__init__.py | 4 ---- .../isaaclab_physx/visualizers/__init__.py | 4 ---- .../isaaclab_physx/visualizers/ov_visualizer.py | 17 ----------------- .../visualizers/ov_visualizer_cfg.py | 4 ---- 4 files changed, 29 deletions(-) diff --git a/source/isaaclab/isaaclab/visualizers/__init__.py b/source/isaaclab/isaaclab/visualizers/__init__.py index a296ae0233c..0667607f410 100644 --- a/source/isaaclab/isaaclab/visualizers/__init__.py +++ b/source/isaaclab/isaaclab/visualizers/__init__.py @@ -3,10 +3,6 @@ # # SPDX-License-Identifier: BSD-3-Clause -# Copyright (c) 2022-2026, The Isaac Lab Project Developers. -# All rights reserved. -# -# SPDX-License-Identifier: BSD-3-Clause """Visualizer Registry. diff --git a/source/isaaclab_physx/isaaclab_physx/visualizers/__init__.py b/source/isaaclab_physx/isaaclab_physx/visualizers/__init__.py index bf63e7d5709..dd59a67b134 100644 --- a/source/isaaclab_physx/isaaclab_physx/visualizers/__init__.py +++ b/source/isaaclab_physx/isaaclab_physx/visualizers/__init__.py @@ -3,10 +3,6 @@ # # SPDX-License-Identifier: BSD-3-Clause -# Copyright (c) 2022-2026, The Isaac Lab Project Developers. -# All rights reserved. -# -# SPDX-License-Identifier: BSD-3-Clause """Sub-package for Omniverse visualizer implementations.""" diff --git a/source/isaaclab_physx/isaaclab_physx/visualizers/ov_visualizer.py b/source/isaaclab_physx/isaaclab_physx/visualizers/ov_visualizer.py index 4be6af38eee..4be60f16b56 100644 --- a/source/isaaclab_physx/isaaclab_physx/visualizers/ov_visualizer.py +++ b/source/isaaclab_physx/isaaclab_physx/visualizers/ov_visualizer.py @@ -3,11 +3,6 @@ # # SPDX-License-Identifier: BSD-3-Clause -# Copyright (c) 2022-2026, The Isaac Lab Project Developers. -# All rights reserved. -# -# SPDX-License-Identifier: BSD-3-Clause - """Omniverse visualizer for Isaac Lab simulation contexts.""" from __future__ import annotations @@ -257,18 +252,6 @@ def is_stopped(self) -> bool: """Check if visualizer is stopped (closed).""" return self._is_closed - def play(self) -> None: - """Start playing (no-op - timeline managed by SimulationContext).""" - pass - - def pause(self) -> None: - """Pause (no-op - timeline managed by SimulationContext).""" - pass - - def stop(self) -> None: - """Stop (no-op - timeline managed by SimulationContext).""" - pass - def supports_markers(self) -> bool: """Supports markers via USD prims.""" return True diff --git a/source/isaaclab_physx/isaaclab_physx/visualizers/ov_visualizer_cfg.py b/source/isaaclab_physx/isaaclab_physx/visualizers/ov_visualizer_cfg.py index 8e8d4823e65..8f2fabd9c9e 100644 --- a/source/isaaclab_physx/isaaclab_physx/visualizers/ov_visualizer_cfg.py +++ b/source/isaaclab_physx/isaaclab_physx/visualizers/ov_visualizer_cfg.py @@ -3,10 +3,6 @@ # # SPDX-License-Identifier: BSD-3-Clause -# Copyright (c) 2022-2026, The Isaac Lab Project Developers. -# All rights reserved. -# -# SPDX-License-Identifier: BSD-3-Clause """Configuration for Omniverse-based visualizer.""" From a570537ca0f8bdd61c47a23c096428e107d70867 Mon Sep 17 00:00:00 2001 From: Octi Zhang Date: Sat, 7 Feb 2026 07:36:49 -0800 Subject: [PATCH 15/46] migrate isaacsim prim usage to isaaclab prim usage --- .../isaaclab/devices/openxr/manus_vive.py | 12 +- .../isaaclab/devices/openxr/openxr_device.py | 9 +- source/isaaclab/test/sensors/test_camera.py | 9 +- .../test/sensors/test_multi_tiled_camera.py | 9 +- .../test/sensors/test_tiled_camera.py | 9 +- .../test/terrains/check_terrain_importer.py | 104 ++++++++++-------- .../test/terrains/test_terrain_importer.py | 95 ++++++++-------- 7 files changed, 136 insertions(+), 111 deletions(-) diff --git a/source/isaaclab/isaaclab/devices/openxr/manus_vive.py b/source/isaaclab/isaaclab/devices/openxr/manus_vive.py index 97791a6fc73..5e15676d482 100644 --- a/source/isaaclab/isaaclab/devices/openxr/manus_vive.py +++ b/source/isaaclab/isaaclab/devices/openxr/manus_vive.py @@ -31,7 +31,7 @@ with contextlib.suppress(ModuleNotFoundError): from omni.kit.xr.core import XRCore -from isaacsim.core.prims import SingleXFormPrim +import isaaclab.sim as sim_utils from .manus_vive_utils import HAND_JOINT_MAP, ManusViveIntegration @@ -92,10 +92,16 @@ 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_prim_path = "/XRAnchor" + sim_utils.create_prim( + xr_anchor_prim_path, + prim_type="Xform", + position=self._xr_cfg.anchor_pos, + orientation=self._xr_cfg.anchor_rot, + ) carb.settings.get_settings().set_float("/persistent/xr/render/nearPlane", self._xr_cfg.near_plane) carb.settings.get_settings().set_string("/persistent/xr/anchorMode", "custom anchor") - carb.settings.get_settings().set_string("/xrstage/customAnchor", xr_anchor.prim_path) + carb.settings.get_settings().set_string("/xrstage/customAnchor", xr_anchor_prim_path) def __del__(self): """Clean up resources when the object is destroyed. diff --git a/source/isaaclab/isaaclab/devices/openxr/openxr_device.py b/source/isaaclab/isaaclab/devices/openxr/openxr_device.py index 8353abca27e..03df180cd5b 100644 --- a/source/isaaclab/isaaclab/devices/openxr/openxr_device.py +++ b/source/isaaclab/isaaclab/devices/openxr/openxr_device.py @@ -35,7 +35,7 @@ with contextlib.suppress(ModuleNotFoundError): from omni.kit.xr.core import XRCore, XRCoreEventType, XRPoseValidityFlags -from isaacsim.core.prims import SingleXFormPrim +import isaaclab.sim as sim_utils class OpenXRDevice(DeviceBase): @@ -105,8 +105,11 @@ def __init__( else: self._xr_anchor_headset_path = "/World/XRAnchor" - _ = SingleXFormPrim( - self._xr_anchor_headset_path, position=self._xr_cfg.anchor_pos, orientation=self._xr_cfg.anchor_rot + sim_utils.create_prim( + self._xr_anchor_headset_path, + prim_type="Xform", + position=self._xr_cfg.anchor_pos, + orientation=self._xr_cfg.anchor_rot, ) if hasattr(carb, "settings"): diff --git a/source/isaaclab/test/sensors/test_camera.py b/source/isaaclab/test/sensors/test_camera.py index 6f44602051b..ff43bc2a07b 100644 --- a/source/isaaclab/test/sensors/test_camera.py +++ b/source/isaaclab/test/sensors/test_camera.py @@ -26,7 +26,6 @@ from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg import omni.replicator.core as rep -from isaacsim.core.prims import SingleGeometryPrim, SingleRigidPrim from pxr import Gf, Usd, UsdGeom import isaaclab.sim as sim_utils @@ -941,6 +940,8 @@ def _populate_scene(): color = Gf.Vec3f(random.random(), random.random(), random.random()) 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) + # add rigid body and collision properties using Isaac Lab schemas + prim_path = f"/World/Objects/Obj_{i:02d}" + sim_utils.define_rigid_body_properties(prim_path, sim_utils.RigidBodyPropertiesCfg()) + sim_utils.define_mass_properties(prim_path, sim_utils.MassPropertiesCfg(mass=5.0)) + sim_utils.define_collision_properties(prim_path, sim_utils.CollisionPropertiesCfg()) diff --git a/source/isaaclab/test/sensors/test_multi_tiled_camera.py b/source/isaaclab/test/sensors/test_multi_tiled_camera.py index b3ef7e2552e..14d29326852 100644 --- a/source/isaaclab/test/sensors/test_multi_tiled_camera.py +++ b/source/isaaclab/test/sensors/test_multi_tiled_camera.py @@ -25,7 +25,6 @@ from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg import omni.replicator.core as rep -from isaacsim.core.prims import SingleGeometryPrim, SingleRigidPrim from pxr import Gf, UsdGeom import isaaclab.sim as sim_utils @@ -508,6 +507,8 @@ def _populate_scene(): color = Gf.Vec3f(random.random(), random.random(), random.random()) 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) + # add rigid body and collision properties using Isaac Lab schemas + prim_path = f"/World/Objects/Obj_{i:02d}" + sim_utils.define_rigid_body_properties(prim_path, sim_utils.RigidBodyPropertiesCfg()) + sim_utils.define_mass_properties(prim_path, sim_utils.MassPropertiesCfg(mass=5.0)) + sim_utils.define_collision_properties(prim_path, sim_utils.CollisionPropertiesCfg()) diff --git a/source/isaaclab/test/sensors/test_tiled_camera.py b/source/isaaclab/test/sensors/test_tiled_camera.py index d11092802cc..848fc890ee5 100644 --- a/source/isaaclab/test/sensors/test_tiled_camera.py +++ b/source/isaaclab/test/sensors/test_tiled_camera.py @@ -24,7 +24,6 @@ from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg import omni.replicator.core as rep -from isaacsim.core.prims import SingleGeometryPrim, SingleRigidPrim from pxr import Gf, UsdGeom import isaaclab.sim as sim_utils @@ -1825,6 +1824,8 @@ def _populate_scene(): color = Gf.Vec3f(random.random(), random.random(), random.random()) 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) + # add rigid body and collision properties using Isaac Lab schemas + prim_path = f"/World/Objects/Obj_{i:02d}" + sim_utils.define_rigid_body_properties(prim_path, sim_utils.RigidBodyPropertiesCfg()) + sim_utils.define_mass_properties(prim_path, sim_utils.MassPropertiesCfg(mass=5.0)) + sim_utils.define_collision_properties(prim_path, sim_utils.CollisionPropertiesCfg()) diff --git a/source/isaaclab/test/terrains/check_terrain_importer.py b/source/isaaclab/test/terrains/check_terrain_importer.py index d88ec65c86d..53045752838 100644 --- a/source/isaaclab/test/terrains/check_terrain_importer.py +++ b/source/isaaclab/test/terrains/check_terrain_importer.py @@ -62,16 +62,10 @@ """Rest everything follows.""" -import numpy as np +import torch -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.cloner import GridCloner -from isaacsim.core.prims import RigidPrim, SingleGeometryPrim, SingleRigidPrim -from isaacsim.core.utils.extensions import enable_extension +from isaacsim.core.simulation_manager import SimulationManager import isaaclab.sim as sim_utils import isaaclab.terrains as terrain_gen @@ -80,8 +74,6 @@ from isaaclab.terrains.terrain_importer import TerrainImporter from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR -enable_extension("omni.kit.primitive.mesh") - def main(): """Generates a terrain from isaaclab.""" @@ -116,59 +108,79 @@ def main(): # -- Light cfg = sim_utils.DistantLightCfg(intensity=1000.0) cfg.func("/World/Light", cfg) - # -- Ball + + # -- Ball with physics properties using Isaac Lab spawners + ball_prim_path = "/World/envs/env_0/ball" + + # Create physics material + physics_material_cfg = sim_utils.RigidBodyMaterialCfg( + static_friction=0.2, + dynamic_friction=1.0, + restitution=0.0, + ) + + # Create visual material + visual_material_cfg = sim_utils.PreviewSurfaceCfg(diffuse_color=(0.0, 0.0, 1.0)) + if args_cli.geom_sphere: - # -- Ball physics - _ = DynamicSphere( - prim_path="/World/envs/env_0/ball", translation=np.array([0.0, 0.0, 5.0]), mass=0.5, radius=0.25 + # Spawn a geom sphere with rigid body properties + sphere_cfg = sim_utils.SphereCfg( + radius=0.25, + rigid_props=sim_utils.RigidBodyPropertiesCfg(), + mass_props=sim_utils.MassPropertiesCfg(mass=0.5), + collision_props=sim_utils.CollisionPropertiesCfg(), + visual_material=visual_material_cfg, + physics_material=physics_material_cfg, ) + sphere_cfg.func(ball_prim_path, sphere_cfg, translation=(0.0, 0.0, 5.0)) else: - # -- Ball geometry - cube_prim_path = omni.kit.commands.execute("CreateMeshPrimCommand", prim_type="Sphere")[1] - sim_utils.move_prim(cube_prim_path, "/World/envs/env_0/ball") - # -- Ball physics - 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) + # Spawn a mesh sphere with rigid body properties + mesh_sphere_cfg = sim_utils.MeshSphereCfg( + radius=0.25, + rigid_props=sim_utils.RigidBodyPropertiesCfg(), + mass_props=sim_utils.MassPropertiesCfg(mass=0.5), + collision_props=sim_utils.CollisionPropertiesCfg(collision_enabled=True), + visual_material=visual_material_cfg, + physics_material=physics_material_cfg, ) - 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( - prim_path="/World/Looks/ballPhysicsMaterial", - dynamic_friction=1.0, - static_friction=0.2, - restitution=0.0, - ) - sphere_geom.set_collision_approximation("convexHull") - sphere_geom.apply_visual_material(visual_material) - sphere_geom.apply_physics_material(physics_material) + mesh_sphere_cfg.func(ball_prim_path, mesh_sphere_cfg, translation=(0.0, 0.0, 0.5)) # Clone the scene cloner.define_base_env("/World/envs") envs_prim_paths = cloner.generate_paths("/World/envs/env", num_paths=num_balls) cloner.clone(source_prim_path="/World/envs/env_0", prim_paths=envs_prim_paths, replicate_physics=True) - physics_scene_path = sim.get_physics_context().prim_path + physics_scene_path = sim.cfg.physics_manager_cfg.physics_prim_path cloner.filter_collisions( physics_scene_path, "/World/collisions", prim_paths=envs_prim_paths, global_paths=["/World/ground"] ) - # Set ball positions over terrain origins - # Create a view over all the balls - ball_view = RigidPrim("/World/envs/env_.*/ball", reset_xform_properties=False) + # Set ball positions over terrain origins using XformPrimView (before simulation starts) + xform_view = sim_utils.XformPrimView("/World/envs/env_.*/ball") # cache initial state of the balls - ball_initial_positions = terrain_importer.env_origins + ball_initial_positions = terrain_importer.env_origins.clone() ball_initial_positions[:, 2] += 5.0 - # set initial poses - # note: setting here writes to USD :) - ball_view.set_world_poses(positions=ball_initial_positions) + # set initial poses (writes to USD before simulation) + xform_view.set_world_poses(positions=ball_initial_positions) # Play simulator sim.reset() - # Initialize the ball views for physics simulation - ball_view.initialize() + + # Create a PhysX rigid body view for physics simulation + physics_sim_view = SimulationManager.get_physics_sim_view() + ball_view = physics_sim_view.create_rigid_body_view("/World/envs/env_*/ball") + + # Cache initial velocities (all zeros) ball_initial_velocities = ball_view.get_velocities() + # Build initial transforms tensor for reset: (N, 7) = [pos(3), quat_xyzw(4)] + num_balls_actual = ball_initial_positions.shape[0] + ball_initial_transforms = torch.zeros(num_balls_actual, 7, device=ball_initial_positions.device) + ball_initial_transforms[:, :3] = ball_initial_positions + ball_initial_transforms[:, 6] = 1.0 # w=1 for identity quaternion (xyzw format) + + # Create indices for all balls (required by PhysX view API) + all_indices = torch.arange(num_balls_actual, dtype=torch.int32, device=ball_initial_positions.device) + # Create a counter for resetting the scene step_count = 0 # Simulate physics @@ -182,9 +194,9 @@ def main(): continue # Reset the scene if step_count % 500 == 0: - # reset the balls - ball_view.set_world_poses(positions=ball_initial_positions) - ball_view.set_velocities(ball_initial_velocities) + # reset the balls using PhysX tensor API + ball_view.set_transforms(ball_initial_transforms, all_indices) + ball_view.set_velocities(ball_initial_velocities, all_indices) # reset the counter step_count = 0 # Step simulation diff --git a/source/isaaclab/test/terrains/test_terrain_importer.py b/source/isaaclab/test/terrains/test_terrain_importer.py index 05ed76e0811..a02b55fd178 100644 --- a/source/isaaclab/test/terrains/test_terrain_importer.py +++ b/source/isaaclab/test/terrains/test_terrain_importer.py @@ -19,13 +19,8 @@ import torch import trimesh -import omni.kit -import omni.kit.commands -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 isaacsim.core.simulation_manager import SimulationManager from pxr import Usd, UsdGeom import isaaclab.sim as sim_utils @@ -174,13 +169,12 @@ def test_ball_drop(device): # Create a scene with rough terrain and balls _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) - # Play simulator sim.reset() - # Initialize the ball views for physics simulation - ball_view.initialize() + + # Create a view over all the balls using PhysX view + physics_sim_view = SimulationManager.get_physics_sim_view() + ball_view = physics_sim_view.create_rigid_body_view("/World/envs/env_*/ball") # Run simulator for _ in range(500): @@ -188,7 +182,8 @@ def test_ball_drop(device): # Ball may have some small non-zero velocity if the roll on terrain <~.2 # If balls fall through terrain velocity is much higher ~82.0 - max_velocity_z = torch.max(torch.abs(ball_view.get_linear_velocities()[:, 2])) + velocities = ball_view.get_velocities() + max_velocity_z = torch.max(torch.abs(velocities[:, 2])) assert max_velocity_z.item() <= 0.5 @@ -207,13 +202,12 @@ def test_ball_drop_geom_sphere(device): # the issue is fixed. _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) - # Play simulator sim.reset() - # Initialize the ball views for physics simulation - ball_view.initialize() + + # Create a view over all the balls using PhysX view + physics_sim_view = SimulationManager.get_physics_sim_view() + ball_view = physics_sim_view.create_rigid_body_view("/World/envs/env_*/ball") # Run simulator for _ in range(500): @@ -221,7 +215,8 @@ def test_ball_drop_geom_sphere(device): # Ball may have some small non-zero velocity if the roll on terrain <~.2 # If balls fall through terrain velocity is much higher ~82.0 - max_velocity_z = torch.max(torch.abs(ball_view.get_linear_velocities()[:, 2])) + velocities = ball_view.get_velocities() + max_velocity_z = torch.max(torch.abs(velocities[:, 2])) assert max_velocity_z.item() <= 0.5 @@ -280,35 +275,41 @@ def _populate_scene(sim: SimulationContext, num_balls: int = 2048, geom_sphere: sim.stage.DefinePrim("/World/envs/env_0", "Xform") # Define the scene - # -- Ball - if geom_sphere: - # -- Ball physics - _ = 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") - cube_prim_path = omni.kit.commands.execute("CreateMeshPrimCommand", prim_type="Sphere")[1] - sim_utils.move_prim(cube_prim_path, "/World/envs/env_0/ball") - # -- Ball physics - 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) + # -- Ball with physics properties using Isaac Lab spawners + ball_prim_path = "/World/envs/env_0/ball" - # -- 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( - prim_path="/World/Looks/ballPhysicsMaterial", - dynamic_friction=1.0, + # Create physics material + physics_material_cfg = sim_utils.RigidBodyMaterialCfg( static_friction=0.2, + dynamic_friction=1.0, restitution=0.0, ) - sphere_geom.set_collision_approximation("convexHull") - sphere_geom.apply_visual_material(visual_material) - sphere_geom.apply_physics_material(physics_material) + + # Create visual material + visual_material_cfg = sim_utils.PreviewSurfaceCfg(diffuse_color=(0.0, 0.0, 1.0)) + + if geom_sphere: + # Spawn a geom sphere with rigid body properties + sphere_cfg = sim_utils.SphereCfg( + radius=0.25, + rigid_props=sim_utils.RigidBodyPropertiesCfg(), + mass_props=sim_utils.MassPropertiesCfg(mass=0.5), + collision_props=sim_utils.CollisionPropertiesCfg(), + visual_material=visual_material_cfg, + physics_material=physics_material_cfg, + ) + sphere_cfg.func(ball_prim_path, sphere_cfg, translation=(0.0, 0.0, 5.0)) + else: + # Spawn a mesh sphere with rigid body properties + mesh_sphere_cfg = sim_utils.MeshSphereCfg( + radius=0.25, + rigid_props=sim_utils.RigidBodyPropertiesCfg(), + mass_props=sim_utils.MassPropertiesCfg(mass=0.5), + collision_props=sim_utils.CollisionPropertiesCfg(collision_enabled=True), + visual_material=visual_material_cfg, + physics_material=physics_material_cfg, + ) + mesh_sphere_cfg.func(ball_prim_path, mesh_sphere_cfg, translation=(0.0, 0.0, 0.5)) # Clone the scene cloner.define_base_env("/World/envs") @@ -318,16 +319,16 @@ def _populate_scene(sim: SimulationContext, num_balls: int = 2048, geom_sphere: prim_paths=envs_prim_paths, replicate_physics=True, ) - physics_scene_path = sim.get_physics_context().prim_path + physics_scene_path = sim.cfg.physics_manager_cfg.physics_prim_path cloner.filter_collisions( physics_scene_path, "/World/collisions", prim_paths=envs_prim_paths, global_paths=["/World/ground"] ) # Set ball positions over terrain origins - # Create a view over all the balls - ball_view = RigidPrim("/World/envs/env_.*/ball", reset_xform_properties=False) + # Create a view over all the balls using Isaac Lab's XformPrimView + ball_view = sim_utils.XformPrimView("/World/envs/env_.*/ball") # cache initial state of the balls - ball_initial_positions = terrain_importer.env_origins + ball_initial_positions = terrain_importer.env_origins.clone() ball_initial_positions[:, 2] += 5.0 # set initial poses # note: setting here writes to USD :) From cdc03b68ebe952e81b820c24a4bd06085fc82b52 Mon Sep 17 00:00:00 2001 From: Octi Zhang Date: Sat, 7 Feb 2026 10:21:56 -0800 Subject: [PATCH 16/46] fix problematic double nested deformable test --- source/isaaclab_physx/test/assets/test_deformable_object.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/source/isaaclab_physx/test/assets/test_deformable_object.py b/source/isaaclab_physx/test/assets/test_deformable_object.py index 666dbcfde7c..1ec9bd916e5 100644 --- a/source/isaaclab_physx/test/assets/test_deformable_object.py +++ b/source/isaaclab_physx/test/assets/test_deformable_object.py @@ -263,12 +263,12 @@ def test_set_nodal_state(sim, num_cubes): @pytest.mark.parametrize("randomize_rot", [True, False]) @flaky(max_runs=3, min_passes=1) @pytest.mark.isaacsim_ci -def test_set_nodal_state_with_applied_transform(sim, num_cubes, randomize_pos, randomize_rot): +def test_set_nodal_state_with_applied_transform(num_cubes, randomize_pos, randomize_rot): """Test setting the state of the deformable object with applied transform.""" carb_settings_iface = carb.settings.get_settings() carb_settings_iface.set_bool("/physics/cooking/ujitsoCollisionCooking", False) - # Create a new simulation context with gravity disabled + # Create simulation context with gravity disabled (no fixture needed) with build_simulation_context(auto_add_lighting=True, gravity_enabled=False) as sim: sim._app_control_on_stop_handle = None cube_object = generate_cubes_scene(num_cubes=num_cubes) From f61fe1843dbba0b40d29fd5f47a1e424fad30d6f Mon Sep 17 00:00:00 2001 From: Octi Zhang Date: Sun, 8 Feb 2026 10:37:50 -0800 Subject: [PATCH 17/46] fixes bugs --- .../benchmarks/benchmark_view_comparison.py | 2 - .../benchmarks/benchmark_xform_prim_view.py | 2 - .../isaaclab/devices/openxr/openxr_device.py | 15 +++-- .../test/controllers/test_differential_ik.py | 2 - .../controllers/test_operational_space.py | 4 +- .../test/deps/isaacsim/check_ref_count.py | 2 +- .../isaaclab/test/devices/test_oxr_device.py | 38 +++++++------ .../test/scene/test_interactive_scene.py | 56 +------------------ source/isaaclab/test/sensors/test_camera.py | 1 - .../test_multi_mesh_ray_caster_camera.py | 1 - .../test/sensors/test_multi_tiled_camera.py | 1 - .../test/sensors/test_ray_caster_camera.py | 1 - .../test/sensors/test_tiled_camera.py | 1 - .../isaaclab/test/sim/test_mesh_converter.py | 2 - .../isaaclab/test/sim/test_mjcf_converter.py | 4 +- source/isaaclab/test/sim/test_schemas.py | 2 - .../sim/test_simulation_stage_in_memory.py | 2 - .../test/sim/test_spawn_from_files.py | 2 - source/isaaclab/test/sim/test_spawn_lights.py | 2 - .../isaaclab/test/sim/test_spawn_materials.py | 2 - source/isaaclab/test/sim/test_spawn_meshes.py | 4 +- .../isaaclab/test/sim/test_spawn_sensors.py | 4 +- source/isaaclab/test/sim/test_spawn_shapes.py | 2 - .../isaaclab/test/sim/test_spawn_wrappers.py | 2 - .../isaaclab/test/sim/test_urdf_converter.py | 2 - .../test/sensors/test_visuotactile_sensor.py | 1 - .../isaaclab_physx/physics/physx_manager.py | 6 ++ .../test/sensors/test_frame_transformer.py | 19 +++---- .../isaaclab_physx/test/sensors/test_imu.py | 22 +++----- 29 files changed, 60 insertions(+), 144 deletions(-) diff --git a/scripts/benchmarks/benchmark_view_comparison.py b/scripts/benchmarks/benchmark_view_comparison.py index a4029371c4a..c995047ac35 100644 --- a/scripts/benchmarks/benchmark_view_comparison.py +++ b/scripts/benchmarks/benchmark_view_comparison.py @@ -199,8 +199,6 @@ def benchmark_view(view_type: str, num_iterations: int) -> tuple[dict[str, float computed_results["world_orientations_after_set"] = orientations_after_set.clone() # close simulation - sim.clear() - sim.clear_all_callbacks() sim.clear_instance() return timing_results, computed_results diff --git a/scripts/benchmarks/benchmark_xform_prim_view.py b/scripts/benchmarks/benchmark_xform_prim_view.py index 94a8dc74361..e76796e2027 100644 --- a/scripts/benchmarks/benchmark_xform_prim_view.py +++ b/scripts/benchmarks/benchmark_xform_prim_view.py @@ -274,8 +274,6 @@ def benchmark_xform_prim_view( # noqa: C901 timing_results["interleaved_world_set_get"] = (time.perf_counter() - start_time) / num_iterations # close simulation - sim.clear() - sim.clear_all_callbacks() sim.clear_instance() return timing_results, computed_results diff --git a/source/isaaclab/isaaclab/devices/openxr/openxr_device.py b/source/isaaclab/isaaclab/devices/openxr/openxr_device.py index 03df180cd5b..23295871ba8 100644 --- a/source/isaaclab/isaaclab/devices/openxr/openxr_device.py +++ b/source/isaaclab/isaaclab/devices/openxr/openxr_device.py @@ -105,12 +105,15 @@ def __init__( else: self._xr_anchor_headset_path = "/World/XRAnchor" - sim_utils.create_prim( - self._xr_anchor_headset_path, - prim_type="Xform", - position=self._xr_cfg.anchor_pos, - orientation=self._xr_cfg.anchor_rot, - ) + # Only create the anchor prim if it doesn't already exist (supports multiple devices sharing anchor) + stage = sim_utils.get_current_stage() + if not stage.GetPrimAtPath(self._xr_anchor_headset_path).IsValid(): + sim_utils.create_prim( + self._xr_anchor_headset_path, + prim_type="Xform", + position=self._xr_cfg.anchor_pos, + orientation=self._xr_cfg.anchor_rot, + ) if hasattr(carb, "settings"): carb.settings.get_settings().set_float("/persistent/xr/render/nearPlane", self._xr_cfg.near_plane) diff --git a/source/isaaclab/test/controllers/test_differential_ik.py b/source/isaaclab/test/controllers/test_differential_ik.py index cd75ca9da38..f2ec6851bdc 100644 --- a/source/isaaclab/test/controllers/test_differential_ik.py +++ b/source/isaaclab/test/controllers/test_differential_ik.py @@ -78,8 +78,6 @@ def sim(): # Cleanup sim.stop() - sim.clear() - sim.clear_all_callbacks() sim.clear_instance() diff --git a/source/isaaclab/test/controllers/test_operational_space.py b/source/isaaclab/test/controllers/test_operational_space.py index 2a7cab03908..bd0a63a717c 100644 --- a/source/isaaclab/test/controllers/test_operational_space.py +++ b/source/isaaclab/test/controllers/test_operational_space.py @@ -223,9 +223,7 @@ def sim(): ) # Cleanup - sim.stop() - sim.clear() - sim.clear_all_callbacks() + sim.stop() sim.clear_instance() diff --git a/source/isaaclab/test/deps/isaacsim/check_ref_count.py b/source/isaaclab/test/deps/isaacsim/check_ref_count.py index 9339afc51fb..c0380183a28 100644 --- a/source/isaaclab/test/deps/isaacsim/check_ref_count.py +++ b/source/isaaclab/test/deps/isaacsim/check_ref_count.py @@ -144,7 +144,7 @@ def main(): print("---" * 10) # Clean up - sim.clear() + sim.clear_instance() print("Reference count of the robot view: ", ctypes.c_long.from_address(id(robot)).value) print("Referrers of the robot view: ", gc.get_referrers(robot)) diff --git a/source/isaaclab/test/devices/test_oxr_device.py b/source/isaaclab/test/devices/test_oxr_device.py index c2e507eb8fe..f474f49eaec 100644 --- a/source/isaaclab/test/devices/test_oxr_device.py +++ b/source/isaaclab/test/devices/test_oxr_device.py @@ -25,8 +25,8 @@ import carb import omni.usd -from isaacsim.core.prims import XFormPrim +import isaaclab.sim as sim_utils from isaaclab.devices import OpenXRDevice, OpenXRDeviceCfg from isaaclab.devices.openxr import XrCfg from isaaclab.devices.retargeter_base import RetargeterBase, RetargeterCfg @@ -175,17 +175,19 @@ def empty_env(): def test_xr_anchor(empty_env, mock_xrcore): """Test XR anchor creation and configuration.""" env, env_cfg = empty_env - env_cfg.xr = XrCfg(anchor_pos=(1, 2, 3), anchor_rot=(1, 0, 0, 0)) + # Use xyzw format for quaternion: identity is (0, 0, 0, 1) + env_cfg.xr = XrCfg(anchor_pos=(1, 2, 3), anchor_rot=(0, 0, 0, 1)) 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") - assert xr_anchor_prim.is_valid() + xr_anchor_view = sim_utils.XformPrimView("/World/XRAnchor") + assert xr_anchor_view.count == 1 - position, orientation = xr_anchor_prim.get_world_poses() - np.testing.assert_almost_equal(position.tolist(), [[1, 2, 3]]) - np.testing.assert_almost_equal(orientation.tolist(), [[1, 0, 0, 0]]) + position, orientation = xr_anchor_view.get_world_poses() + np.testing.assert_almost_equal(position.cpu().numpy(), [[1, 2, 3]]) + # XformPrimView returns quaternion in xyzw format, identity is [0, 0, 0, 1] + np.testing.assert_almost_equal(orientation.cpu().numpy(), [[0, 0, 0, 1]]) # Check that xr anchor mode and custom anchor are set correctly assert carb.settings.get_settings().get("/persistent/xr/anchorMode") == "custom anchor" @@ -202,12 +204,13 @@ 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") - assert xr_anchor_prim.is_valid() + xr_anchor_view = sim_utils.XformPrimView("/World/XRAnchor") + assert xr_anchor_view.count == 1 - position, orientation = xr_anchor_prim.get_world_poses() - np.testing.assert_almost_equal(position.tolist(), [[0, 0, 0]]) - np.testing.assert_almost_equal(orientation.tolist(), [[0, 0, 0, 1]]) + position, orientation = xr_anchor_view.get_world_poses() + np.testing.assert_almost_equal(position.cpu().numpy(), [[0, 0, 0]]) + # XformPrimView returns quaternion in xyzw format, identity is [0, 0, 0, 1] + np.testing.assert_almost_equal(orientation.cpu().numpy(), [[0, 0, 0, 1]]) # Check that xr anchor mode and custom anchor are set correctly assert carb.settings.get_settings().get("/persistent/xr/anchorMode") == "custom anchor" @@ -225,12 +228,13 @@ 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") - assert xr_anchor_prim.is_valid() + xr_anchor_view = sim_utils.XformPrimView("/World/XRAnchor") + assert xr_anchor_view.count == 1 - position, orientation = xr_anchor_prim.get_world_poses() - np.testing.assert_almost_equal(position.tolist(), [[0, 0, 0]]) - np.testing.assert_almost_equal(orientation.tolist(), [[0, 0, 0, 1]]) + position, orientation = xr_anchor_view.get_world_poses() + np.testing.assert_almost_equal(position.cpu().numpy(), [[0, 0, 0]]) + # XformPrimView returns quaternion in xyzw format, identity is [0, 0, 0, 1] + np.testing.assert_almost_equal(orientation.cpu().numpy(), [[0, 0, 0, 1]]) # Check that xr anchor mode and custom anchor are set correctly assert carb.settings.get_settings().get("/persistent/xr/anchorMode") == "custom anchor" diff --git a/source/isaaclab/test/scene/test_interactive_scene.py b/source/isaaclab/test/scene/test_interactive_scene.py index 1a42a340baa..97f882dbfb8 100644 --- a/source/isaaclab/test/scene/test_interactive_scene.py +++ b/source/isaaclab/test/scene/test_interactive_scene.py @@ -17,9 +17,8 @@ import isaaclab.sim as sim_utils from isaaclab.actuators import ImplicitActuatorCfg -from isaaclab.assets import ArticulationCfg, AssetBaseCfg, RigidObjectCfg +from isaaclab.assets import ArticulationCfg, RigidObjectCfg from isaaclab.scene import InteractiveScene, InteractiveSceneCfg -from isaaclab.sensors import ContactSensorCfg from isaaclab.sim import build_simulation_context from isaaclab.utils import configclass from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR @@ -33,7 +32,7 @@ class MySceneCfg(InteractiveSceneCfg): robot = ArticulationCfg( prim_path="/World/envs/env_.*/Robot", spawn=sim_utils.UsdFileCfg( - usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/IsaacSim/SimpleArticulation/revolute_articulation.usd" + usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/IsaacSim/SimpleArticulation/revolute_articulation.usd", ), actuators={ "joint": ImplicitActuatorCfg(joint_names_expr=[".*"], stiffness=100.0, damping=1.0), @@ -66,56 +65,7 @@ def make_scene(num_envs: int, env_spacing: float = 1.0): return scene_cfg yield make_scene, sim - sim.stop() - sim.clear() - sim.clear_all_callbacks() - sim.clear_instance() - - -@pytest.mark.parametrize("device", ["cuda:0", "cpu"]) -def test_scene_entity_isolation(device, setup_scene): - """Tests that multiple instances of InteractiveScene do not share any data. - - In this test, two InteractiveScene instances are created in a loop and added to a list. - The scene at index 0 of the list will have all of its entities cleared manually, and - the test compares that the data held in the scene at index 1 remained intact. - """ - make_scene, sim = setup_scene - scene_cfg = make_scene(num_envs=1) - # set additional light to test 'extras' attribute of the scene - setattr( - scene_cfg, - "light", - AssetBaseCfg( - prim_path="/World/light", - spawn=sim_utils.DistantLightCfg(), - ), - ) - # set additional sensor to test 'sensors' attribute of the scene - setattr(scene_cfg, "sensor", ContactSensorCfg(prim_path="/World/envs/env_.*/Robot")) - - scene_list = [] - # create two InteractiveScene instances - for _ in range(2): - with build_simulation_context(device=device, dt=sim.get_physics_dt()) as _: - scene = InteractiveScene(scene_cfg) - scene_list.append(scene) - scene_0 = scene_list[0] - scene_1 = scene_list[1] - # clear entities for scene_0 - this should not affect any data in scene_1 - scene_0.articulations.clear() - scene_0.rigid_objects.clear() - scene_0.sensors.clear() - scene_0.extras.clear() - # check that scene_0 and scene_1 do not share entity data via dictionary comparison - assert scene_0.articulations == dict() - assert scene_0.articulations != scene_1.articulations - assert scene_0.rigid_objects == dict() - assert scene_0.rigid_objects != scene_1.rigid_objects - assert scene_0.sensors == dict() - assert scene_0.sensors != scene_1.sensors - assert scene_0.extras == dict() - assert scene_0.extras != scene_1.extras + # Note: cleanup is handled by build_simulation_context's finally block @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) diff --git a/source/isaaclab/test/sensors/test_camera.py b/source/isaaclab/test/sensors/test_camera.py index ff43bc2a07b..66abc398f87 100644 --- a/source/isaaclab/test/sensors/test_camera.py +++ b/source/isaaclab/test/sensors/test_camera.py @@ -80,7 +80,6 @@ def teardown(sim: sim_utils.SimulationContext): # note: cannot use self.sim.stop() since it does one render step after stopping!! This doesn't make sense :( sim._timeline.stop() # clear the stage - sim.clear_all_callbacks() sim.clear_instance() diff --git a/source/isaaclab/test/sensors/test_multi_mesh_ray_caster_camera.py b/source/isaaclab/test/sensors/test_multi_mesh_ray_caster_camera.py index 38e2faae0f8..31b08e9d36c 100644 --- a/source/isaaclab/test/sensors/test_multi_mesh_ray_caster_camera.py +++ b/source/isaaclab/test/sensors/test_multi_mesh_ray_caster_camera.py @@ -85,7 +85,6 @@ def setup_simulation(): # note: cannot use self.sim.stop() since it does one render step after stopping!! This doesn't make sense :( sim._timeline.stop() # clear the stage - sim.clear_all_callbacks() sim.clear_instance() diff --git a/source/isaaclab/test/sensors/test_multi_tiled_camera.py b/source/isaaclab/test/sensors/test_multi_tiled_camera.py index 14d29326852..3b619160a3a 100644 --- a/source/isaaclab/test/sensors/test_multi_tiled_camera.py +++ b/source/isaaclab/test/sensors/test_multi_tiled_camera.py @@ -63,7 +63,6 @@ def setup_camera(): # note: cannot use self.sim.stop() since it does one render step after stopping!! This doesn't make sense :( sim._timeline.stop() # clear the stage - sim.clear_all_callbacks() sim.clear_instance() diff --git a/source/isaaclab/test/sensors/test_ray_caster_camera.py b/source/isaaclab/test/sensors/test_ray_caster_camera.py index abf64b653f7..5148bfe5bed 100644 --- a/source/isaaclab/test/sensors/test_ray_caster_camera.py +++ b/source/isaaclab/test/sensors/test_ray_caster_camera.py @@ -88,7 +88,6 @@ def teardown(sim: sim_utils.SimulationContext): # note: cannot use self.sim.stop() since it does one render step after stopping!! This doesn't make sense :( sim._timeline.stop() # clear the stage - sim.clear_all_callbacks() sim.clear_instance() diff --git a/source/isaaclab/test/sensors/test_tiled_camera.py b/source/isaaclab/test/sensors/test_tiled_camera.py index 848fc890ee5..8b16be1257f 100644 --- a/source/isaaclab/test/sensors/test_tiled_camera.py +++ b/source/isaaclab/test/sensors/test_tiled_camera.py @@ -61,7 +61,6 @@ def setup_camera(device) -> tuple[sim_utils.SimulationContext, TiledCameraCfg, f # Teardown rep.vp_manager.destroy_hydra_textures("Replicator") sim._timeline.stop() - sim.clear_all_callbacks() sim.clear_instance() diff --git a/source/isaaclab/test/sim/test_mesh_converter.py b/source/isaaclab/test/sim/test_mesh_converter.py index 5d6af838696..731fc4ded5a 100644 --- a/source/isaaclab/test/sim/test_mesh_converter.py +++ b/source/isaaclab/test/sim/test_mesh_converter.py @@ -72,8 +72,6 @@ def sim(): # stop simulation sim.stop() # cleanup stage and context - sim.clear() - sim.clear_all_callbacks() sim.clear_instance() diff --git a/source/isaaclab/test/sim/test_mjcf_converter.py b/source/isaaclab/test/sim/test_mjcf_converter.py index 37eb1e8d452..41b34db4a9b 100644 --- a/source/isaaclab/test/sim/test_mjcf_converter.py +++ b/source/isaaclab/test/sim/test_mjcf_converter.py @@ -48,9 +48,7 @@ def test_setup_teardown(): yield sim, config # Teardown: Cleanup simulation - sim.stop() - sim.clear() - sim.clear_all_callbacks() + sim.stop() sim.clear_instance() diff --git a/source/isaaclab/test/sim/test_schemas.py b/source/isaaclab/test/sim/test_schemas.py index b6ec6360edd..54447d7d777 100644 --- a/source/isaaclab/test/sim/test_schemas.py +++ b/source/isaaclab/test/sim/test_schemas.py @@ -77,8 +77,6 @@ def setup_simulation(): # Teardown sim._disable_app_control_on_stop_handle = True # prevent timeout sim.stop() - sim.clear() - sim.clear_all_callbacks() sim.clear_instance() diff --git a/source/isaaclab/test/sim/test_simulation_stage_in_memory.py b/source/isaaclab/test/sim/test_simulation_stage_in_memory.py index 82dc2087e80..7691e419ccc 100644 --- a/source/isaaclab/test/sim/test_simulation_stage_in_memory.py +++ b/source/isaaclab/test/sim/test_simulation_stage_in_memory.py @@ -39,8 +39,6 @@ def sim(): yield sim omni.physx.get_physx_simulation_interface().detach_stage() sim.stop() - sim.clear() - sim.clear_all_callbacks() sim.clear_instance() diff --git a/source/isaaclab/test/sim/test_spawn_from_files.py b/source/isaaclab/test/sim/test_spawn_from_files.py index bb77eb2c3df..33bdb3e887a 100644 --- a/source/isaaclab/test/sim/test_spawn_from_files.py +++ b/source/isaaclab/test/sim/test_spawn_from_files.py @@ -40,8 +40,6 @@ def sim(): # cleanup after test sim.stop() - sim.clear() - sim.clear_all_callbacks() sim.clear_instance() diff --git a/source/isaaclab/test/sim/test_spawn_lights.py b/source/isaaclab/test/sim/test_spawn_lights.py index 152ef6d83a3..a2676b8887c 100644 --- a/source/isaaclab/test/sim/test_spawn_lights.py +++ b/source/isaaclab/test/sim/test_spawn_lights.py @@ -40,8 +40,6 @@ def sim(): # Teardown: Stop simulation sim.stop() - sim.clear() - sim.clear_all_callbacks() sim.clear_instance() diff --git a/source/isaaclab/test/sim/test_spawn_materials.py b/source/isaaclab/test/sim/test_spawn_materials.py index 28b3d33dbd0..0ef1b81e101 100644 --- a/source/isaaclab/test/sim/test_spawn_materials.py +++ b/source/isaaclab/test/sim/test_spawn_materials.py @@ -32,8 +32,6 @@ def sim(): sim_utils.update_stage() yield sim sim.stop() - sim.clear() - sim.clear_all_callbacks() sim.clear_instance() diff --git a/source/isaaclab/test/sim/test_spawn_meshes.py b/source/isaaclab/test/sim/test_spawn_meshes.py index beb3b7ff5db..0ca2559843e 100644 --- a/source/isaaclab/test/sim/test_spawn_meshes.py +++ b/source/isaaclab/test/sim/test_spawn_meshes.py @@ -34,9 +34,7 @@ def sim(): yield sim # Cleanup sim._disable_app_control_on_stop_handle = True # prevent timeout - sim.stop() - sim.clear() - sim.clear_all_callbacks() + sim.stop() sim.clear_instance() diff --git a/source/isaaclab/test/sim/test_spawn_sensors.py b/source/isaaclab/test/sim/test_spawn_sensors.py index 5672a364271..f66b2e740d5 100644 --- a/source/isaaclab/test/sim/test_spawn_sensors.py +++ b/source/isaaclab/test/sim/test_spawn_sensors.py @@ -32,9 +32,7 @@ def sim(): sim = SimulationContext(SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=dt))) sim_utils.update_stage() yield sim - sim.stop() - sim.clear() - sim.clear_all_callbacks() + sim.stop() sim.clear_instance() diff --git a/source/isaaclab/test/sim/test_spawn_shapes.py b/source/isaaclab/test/sim/test_spawn_shapes.py index f77a113b36c..a5650b5c4ce 100644 --- a/source/isaaclab/test/sim/test_spawn_shapes.py +++ b/source/isaaclab/test/sim/test_spawn_shapes.py @@ -29,8 +29,6 @@ def sim(): yield sim sim._disable_app_control_on_stop_handle = True # prevent timeout sim.stop() - sim.clear() - sim.clear_all_callbacks() sim.clear_instance() diff --git a/source/isaaclab/test/sim/test_spawn_wrappers.py b/source/isaaclab/test/sim/test_spawn_wrappers.py index 2de1e3edaec..10bf2c316a0 100644 --- a/source/isaaclab/test/sim/test_spawn_wrappers.py +++ b/source/isaaclab/test/sim/test_spawn_wrappers.py @@ -30,8 +30,6 @@ def sim(): sim_utils.update_stage() yield sim sim.stop() - sim.clear() - sim.clear_all_callbacks() sim.clear_instance() diff --git a/source/isaaclab/test/sim/test_urdf_converter.py b/source/isaaclab/test/sim/test_urdf_converter.py index 806d049a8f9..ca136fd9f97 100644 --- a/source/isaaclab/test/sim/test_urdf_converter.py +++ b/source/isaaclab/test/sim/test_urdf_converter.py @@ -59,8 +59,6 @@ def sim_config(): # Teardown sim._disable_app_control_on_stop_handle = True # prevent timeout sim.stop() - sim.clear() - sim.clear_all_callbacks() sim.clear_instance() diff --git a/source/isaaclab_contrib/test/sensors/test_visuotactile_sensor.py b/source/isaaclab_contrib/test/sensors/test_visuotactile_sensor.py index 0ac295ea06e..5efdb2627d9 100644 --- a/source/isaaclab_contrib/test/sensors/test_visuotactile_sensor.py +++ b/source/isaaclab_contrib/test/sensors/test_visuotactile_sensor.py @@ -193,7 +193,6 @@ def teardown(sim): # note: cannot use self.sim.stop() since it does one render step after stopping!! This doesn't make sense :( sim._timeline.stop() # clear the stage - sim.clear_all_callbacks() sim.clear_instance() diff --git a/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py b/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py index 7b966e58891..b105ab70662 100644 --- a/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py +++ b/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py @@ -264,16 +264,22 @@ def step(cls) -> None: def play(cls) -> None: """Start or resume the timeline.""" cls._timeline.play() + # Pump events so timeline callbacks fire synchronously + omni.kit.app.get_app().update() @classmethod def pause(cls) -> None: """Pause the timeline.""" cls._timeline.pause() + # Pump events so timeline callbacks fire synchronously + omni.kit.app.get_app().update() @classmethod def stop(cls) -> None: """Stop the timeline.""" cls._timeline.stop() + # Pump events so timeline callbacks fire synchronously + omni.kit.app.get_app().update() @classmethod def close(cls) -> None: diff --git a/source/isaaclab_physx/test/sensors/test_frame_transformer.py b/source/isaaclab_physx/test/sensors/test_frame_transformer.py index 1253e3cbe0d..5509d25ec32 100644 --- a/source/isaaclab_physx/test/sensors/test_frame_transformer.py +++ b/source/isaaclab_physx/test/sensors/test_frame_transformer.py @@ -75,18 +75,13 @@ class MySceneCfg(InteractiveSceneCfg): @pytest.fixture def sim(): """Create a simulation context.""" - # Create a new stage - sim_utils.create_new_stage() - # Load kit helper - sim = sim_utils.SimulationContext( - sim_utils.SimulationCfg(device="cpu", physics_manager_cfg=PhysxManagerCfg(dt=0.005)) - ) - # Set main camera - sim.set_camera_view(eye=(5.0, 5.0, 5.0), target=(0.0, 0.0, 0.0)) - yield sim - # Cleanup - sim.clear_all_callbacks() - sim.clear_instance() + sim_cfg = sim_utils.SimulationCfg(device="cpu", physics_manager_cfg=PhysxManagerCfg(dt=0.005)) + with sim_utils.build_simulation_context(sim_cfg=sim_cfg) as sim: + sim._app_control_on_stop_handle = None + # Set main camera + sim.set_camera_view(eye=(5.0, 5.0, 5.0), target=(0.0, 0.0, 0.0)) + yield sim + # Cleanup is handled by build_simulation_context def test_frame_transformer_feet_wrt_base(sim): diff --git a/source/isaaclab_physx/test/sensors/test_imu.py b/source/isaaclab_physx/test/sensors/test_imu.py index 3bb71c6f336..da5ed4e2503 100644 --- a/source/isaaclab_physx/test/sensors/test_imu.py +++ b/source/isaaclab_physx/test/sensors/test_imu.py @@ -202,22 +202,18 @@ def __post_init__(self): @pytest.fixture def setup_sim(): """Create a simulation context and scene.""" - # Create a new stage - sim_utils.create_new_stage() - # Load simulation context sim_cfg = sim_utils.SimulationCfg( physics_manager_cfg=PhysxManagerCfg(dt=0.001, solver_type=0) ) # 0: PGS, 1: TGS --> use PGS for more accurate results - sim = sim_utils.SimulationContext(sim_cfg) - # construct scene - scene_cfg = MySceneCfg(num_envs=2, env_spacing=5.0, lazy_sensor_update=False) - scene = InteractiveScene(scene_cfg) - # Play the simulator - sim.reset() - yield sim, scene - # Cleanup - sim.clear_all_callbacks() - sim.clear_instance() + with sim_utils.build_simulation_context(sim_cfg=sim_cfg) as sim: + sim._app_control_on_stop_handle = None + # construct scene + scene_cfg = MySceneCfg(num_envs=2, env_spacing=5.0, lazy_sensor_update=False) + scene = InteractiveScene(scene_cfg) + # Play the simulator + sim.reset() + yield sim, scene + # Cleanup is handled by build_simulation_context @pytest.mark.isaacsim_ci From ce190cdb5d896a78eb56a219f3ab0da4cd42646e Mon Sep 17 00:00:00 2001 From: Octi Zhang Date: Sun, 8 Feb 2026 11:22:32 -0800 Subject: [PATCH 18/46] fixes bugs --- .../benchmarks/benchmark_view_comparison.py | 4 +- .../devices/openxr/xr_anchor_utils.py | 2 +- source/isaaclab/isaaclab/sim/utils/stage.py | 20 +---- .../test/terrains/check_terrain_importer.py | 3 +- .../test/terrains/test_terrain_importer.py | 5 +- .../tacsl_sensor/visuotactile_sensor.py | 17 ++-- .../direct/automate/assembly_env.py | 83 ++++++++++--------- .../direct/automate/disassembly_env.py | 73 ++++++++-------- .../direct/automate/factory_control.py | 14 ++-- .../isaaclab_tasks/direct/forge/forge_env.py | 37 +++++---- .../direct/forge/forge_utils.py | 29 +++++-- .../franka_cabinet/franka_cabinet_env.py | 40 +++++---- 12 files changed, 172 insertions(+), 155 deletions(-) diff --git a/scripts/benchmarks/benchmark_view_comparison.py b/scripts/benchmarks/benchmark_view_comparison.py index c995047ac35..1b743135e7c 100644 --- a/scripts/benchmarks/benchmark_view_comparison.py +++ b/scripts/benchmarks/benchmark_view_comparison.py @@ -71,8 +71,6 @@ import torch from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg -from isaacsim.core.simulation_manager import SimulationManager - import isaaclab.sim as sim_utils from isaaclab.sim.views import XformPrimView @@ -141,7 +139,7 @@ def benchmark_view(view_type: str, num_iterations: int) -> tuple[dict[str, float num_prims = view.count view_name = "XformPrimView (Fabric)" else: # physx - physics_sim_view = SimulationManager.get_physics_sim_view() + physics_sim_view = sim.physics_manager.get_physics_sim_view() view = physics_sim_view.create_rigid_body_view(pattern) num_prims = view.count view_name = "PhysX RigidBodyView" diff --git a/source/isaaclab/isaaclab/devices/openxr/xr_anchor_utils.py b/source/isaaclab/isaaclab/devices/openxr/xr_anchor_utils.py index 6bc9fcd6ec2..600e41f2494 100644 --- a/source/isaaclab/isaaclab/devices/openxr/xr_anchor_utils.py +++ b/source/isaaclab/isaaclab/devices/openxr/xr_anchor_utils.py @@ -44,7 +44,7 @@ def __init__(self, xr_core: Any, xr_cfg: Any, xr_anchor_headset_path: str): # Resolve USD layer identifier of the anchor for updates try: - from isaacsim.core.utils.stage import get_current_stage + from isaaclab.sim.utils.stage import get_current_stage stage = get_current_stage() xr_anchor_headset_prim = stage.GetPrimAtPath(self._xr_anchor_headset_path) diff --git a/source/isaaclab/isaaclab/sim/utils/stage.py b/source/isaaclab/isaaclab/sim/utils/stage.py index 88c61744e7d..042063ee2c1 100644 --- a/source/isaaclab/isaaclab/sim/utils/stage.py +++ b/source/isaaclab/isaaclab/sim/utils/stage.py @@ -440,7 +440,6 @@ def attach_stage_to_usd_context(attaching_early: bool = False): import carb import omni.physx import omni.usd - from isaacsim.core.simulation_manager import SimulationManager from isaaclab.sim.simulation_context import SimulationContext @@ -472,21 +471,6 @@ def attach_stage_to_usd_context(attaching_early: bool = False): " does not support stage in memory." ) - # skip this callback to avoid wiping the stage after attachment - SimulationContext.instance().skip_next_stage_open_callback() - - # disable stage open callback to avoid clearing callbacks - SimulationManager.enable_stage_open_callback(False) - - # enable physics fabric - SimulationContext.instance()._physics_context.enable_fabric(True) # type: ignore - - # attach stage to usd context + # Enable physics fabric and attach stage to usd context for rendering + SimulationContext.instance().carb_settings.set_bool("/isaaclab/fabric_enabled", True) omni.usd.get_context().attach_stage_with_callback(stage_id) - - # attach stage to physx - physx_sim_interface = omni.physx.get_physx_simulation_interface() - physx_sim_interface.attach_stage(stage_id) - - # re-enable stage open callback - SimulationManager.enable_stage_open_callback(True) diff --git a/source/isaaclab/test/terrains/check_terrain_importer.py b/source/isaaclab/test/terrains/check_terrain_importer.py index 53045752838..866f07ac516 100644 --- a/source/isaaclab/test/terrains/check_terrain_importer.py +++ b/source/isaaclab/test/terrains/check_terrain_importer.py @@ -65,7 +65,6 @@ import torch from isaacsim.core.cloner import GridCloner -from isaacsim.core.simulation_manager import SimulationManager import isaaclab.sim as sim_utils import isaaclab.terrains as terrain_gen @@ -166,7 +165,7 @@ def main(): sim.reset() # Create a PhysX rigid body view for physics simulation - physics_sim_view = SimulationManager.get_physics_sim_view() + physics_sim_view = sim.physics_manager.get_physics_sim_view() ball_view = physics_sim_view.create_rigid_body_view("/World/envs/env_*/ball") # Cache initial velocities (all zeros) diff --git a/source/isaaclab/test/terrains/test_terrain_importer.py b/source/isaaclab/test/terrains/test_terrain_importer.py index a02b55fd178..ab8384080ca 100644 --- a/source/isaaclab/test/terrains/test_terrain_importer.py +++ b/source/isaaclab/test/terrains/test_terrain_importer.py @@ -20,7 +20,6 @@ import trimesh from isaacsim.core.cloner import GridCloner -from isaacsim.core.simulation_manager import SimulationManager from pxr import Usd, UsdGeom import isaaclab.sim as sim_utils @@ -173,7 +172,7 @@ def test_ball_drop(device): sim.reset() # Create a view over all the balls using PhysX view - physics_sim_view = SimulationManager.get_physics_sim_view() + physics_sim_view = sim.physics_manager.get_physics_sim_view() ball_view = physics_sim_view.create_rigid_body_view("/World/envs/env_*/ball") # Run simulator @@ -206,7 +205,7 @@ def test_ball_drop_geom_sphere(device): sim.reset() # Create a view over all the balls using PhysX view - physics_sim_view = SimulationManager.get_physics_sim_view() + physics_sim_view = sim.physics_manager.get_physics_sim_view() ball_view = physics_sim_view.create_rigid_body_view("/World/envs/env_*/ball") # Run simulator diff --git a/source/isaaclab_contrib/isaaclab_contrib/sensors/tacsl_sensor/visuotactile_sensor.py b/source/isaaclab_contrib/isaaclab_contrib/sensors/tacsl_sensor/visuotactile_sensor.py index 0685e8b593b..8037ecb06a9 100644 --- a/source/isaaclab_contrib/isaaclab_contrib/sensors/tacsl_sensor/visuotactile_sensor.py +++ b/source/isaaclab_contrib/isaaclab_contrib/sensors/tacsl_sensor/visuotactile_sensor.py @@ -14,12 +14,12 @@ import numpy as np import torch -import isaacsim.core.utils.torch as torch_utils -from isaacsim.core.simulation_manager import SimulationManager from pxr import Usd, UsdGeom, UsdPhysics import isaaclab.sim as sim_utils import isaaclab.utils.math as math_utils +from isaaclab.utils.math import quat_apply, quat_inv +from isaaclab.sim import SimulationContext from isaaclab.markers import VisualizationMarkers from isaaclab.sensors.camera import Camera, TiledCamera from isaaclab.sensors.sensor_base import SensorBase @@ -179,7 +179,7 @@ def _initialize_impl(self): super()._initialize_impl() # Obtain global simulation view - self._physics_sim_view = SimulationManager.get_physics_sim_view() + self._physics_sim_view = SimulationContext.instance().physics_manager.get_physics_sim_view() # Initialize camera-based tactile sensing if self.cfg.enable_camera_tactile: @@ -674,17 +674,16 @@ def _transform_points_to_contact_object_local( Points in contact object local coordinates and inverse quaternions """ # Get inverse transformation (per environment) - # wxyz in torch - contact_object_quat_inv, contact_object_pos_inv = torch_utils.tf_inverse( - contact_object_quat_w, contact_object_pos_w - ) + # xyzw quaternion convention + contact_object_quat_inv = quat_inv(contact_object_quat_w) + contact_object_pos_inv = -quat_apply(contact_object_quat_inv, contact_object_pos_w) num_pts = self.num_tactile_points contact_object_quat_expanded = contact_object_quat_inv.unsqueeze(1).expand(-1, num_pts, 4) contact_object_pos_expanded = contact_object_pos_inv.unsqueeze(1).expand(-1, num_pts, 3) - # Apply transformation - points_sdf = torch_utils.tf_apply(contact_object_quat_expanded, contact_object_pos_expanded, world_points) + # Apply transformation: rotate then translate + points_sdf = quat_apply(contact_object_quat_expanded, world_points) + contact_object_pos_expanded return points_sdf, contact_object_quat_inv diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/automate/assembly_env.py b/source/isaaclab_tasks/isaaclab_tasks/direct/automate/assembly_env.py index 5ad81e3b0be..29f47aed0f4 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/automate/assembly_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/automate/assembly_env.py @@ -11,9 +11,16 @@ import warp as wp import carb -import isaacsim.core.utils.torch as torch_utils import isaaclab.sim as sim_utils +from isaaclab.utils.math import ( + combine_frame_transforms, + euler_xyz_from_quat, + quat_conjugate, + quat_from_angle_axis, + quat_from_euler_xyz, + quat_mul, +) from isaaclab.assets import Articulation, RigidObject from isaaclab.envs import DirectRLEnv from isaaclab.sim.spawners.from_files import GroundPlaneCfg, spawn_ground_plane @@ -294,18 +301,18 @@ def _compute_intermediate_values(self, dt): self.joint_vel = self._robot.data.joint_vel.clone() # Compute pose of gripper goal and top of socket in socket frame - self.gripper_goal_quat, self.gripper_goal_pos = torch_utils.tf_combine( - self.fixed_quat, + self.gripper_goal_pos, self.gripper_goal_quat = combine_frame_transforms( self.fixed_pos, - self.plug_grasp_quat_local, + self.fixed_quat, self.plug_grasp_pos_local, + self.plug_grasp_quat_local, ) - self.gripper_goal_quat, self.gripper_goal_pos = torch_utils.tf_combine( - self.gripper_goal_quat, + self.gripper_goal_pos, self.gripper_goal_quat = combine_frame_transforms( self.gripper_goal_pos, - self.robot_to_gripper_quat, + self.gripper_goal_quat, self.palm_to_finger_center, + self.robot_to_gripper_quat, ) # Finite-differencing results in more reliable velocity estimates. @@ -313,8 +320,8 @@ def _compute_intermediate_values(self, dt): self.prev_fingertip_pos = self.fingertip_midpoint_pos.clone() # Add state differences if velocity isn't being added. - rot_diff_quat = torch_utils.quat_mul( - self.fingertip_midpoint_quat, torch_utils.quat_conjugate(self.prev_fingertip_quat) + rot_diff_quat = quat_mul( + self.fingertip_midpoint_quat, quat_conjugate(self.prev_fingertip_quat) ) rot_diff_quat *= torch.sign(rot_diff_quat[:, 3]).unsqueeze(-1) # W component is at index 3 in XYZW format rot_diff_aa = axis_angle_from_quat(rot_diff_quat) @@ -326,24 +333,24 @@ def _compute_intermediate_values(self, dt): self.prev_joint_pos = self.joint_pos[:, 0:7].clone() # Keypoint tensors. - self.held_base_quat[:], self.held_base_pos[:] = torch_utils.tf_combine( - self.held_quat, self.held_pos, self.held_base_quat_local, self.held_base_pos_local + self.held_base_pos[:], self.held_base_quat[:] = combine_frame_transforms( + self.held_pos, self.held_quat, self.held_base_pos_local, self.held_base_quat_local ) - self.target_held_base_quat[:], self.target_held_base_pos[:] = torch_utils.tf_combine( - self.fixed_quat, self.fixed_pos, self.identity_quat, self.fixed_success_pos_local + self.target_held_base_pos[:], self.target_held_base_quat[:] = combine_frame_transforms( + self.fixed_pos, self.fixed_quat, self.fixed_success_pos_local, self.identity_quat ) # Compute pos of keypoints on held asset, and fixed asset in world frame for idx, keypoint_offset in enumerate(self.keypoint_offsets): - self.keypoints_held[:, idx] = torch_utils.tf_combine( - self.held_base_quat, self.held_base_pos, self.identity_quat, keypoint_offset.repeat(self.num_envs, 1) - )[1] - self.keypoints_fixed[:, idx] = torch_utils.tf_combine( - self.target_held_base_quat, + self.keypoints_held[:, idx] = combine_frame_transforms( + self.held_base_pos, self.held_base_quat, keypoint_offset.repeat(self.num_envs, 1), self.identity_quat + )[0] + self.keypoints_fixed[:, idx] = combine_frame_transforms( self.target_held_base_pos, - self.identity_quat, + self.target_held_base_quat, keypoint_offset.repeat(self.num_envs, 1), - )[1] + self.identity_quat, + )[0] self.keypoint_dist = torch.norm(self.keypoints_held - self.keypoints_fixed, p=2, dim=-1).mean(-1) self.last_update_timestamp = self._robot._data._sim_timestamp @@ -413,20 +420,20 @@ def move_gripper_in_place(self, ctrl_target_gripper_dof_pos): angle = torch.norm(rot_actions, p=2, dim=-1) axis = rot_actions / angle.unsqueeze(-1) - rot_actions_quat = torch_utils.quat_from_angle_axis(angle, axis) + rot_actions_quat = quat_from_angle_axis(angle, axis) rot_actions_quat = torch.where( angle.unsqueeze(-1).repeat(1, 4) > 1.0e-6, rot_actions_quat, torch.tensor([0.0, 0.0, 0.0, 1.0], device=self.device).repeat(self.num_envs, 1), ) - self.ctrl_target_fingertip_midpoint_quat = torch_utils.quat_mul(rot_actions_quat, self.fingertip_midpoint_quat) + self.ctrl_target_fingertip_midpoint_quat = quat_mul(rot_actions_quat, self.fingertip_midpoint_quat) - target_euler_xyz = torch.stack(torch_utils.get_euler_xyz(self.ctrl_target_fingertip_midpoint_quat), dim=1) + target_euler_xyz = torch.stack(euler_xyz_from_quat(self.ctrl_target_fingertip_midpoint_quat), dim=1) target_euler_xyz[:, 0] = 3.14159 target_euler_xyz[:, 1] = 0.0 - self.ctrl_target_fingertip_midpoint_quat = torch_utils.quat_from_euler_xyz( + self.ctrl_target_fingertip_midpoint_quat = quat_from_euler_xyz( roll=target_euler_xyz[:, 0], pitch=target_euler_xyz[:, 1], yaw=target_euler_xyz[:, 2] ) @@ -436,7 +443,7 @@ def move_gripper_in_place(self, ctrl_target_gripper_dof_pos): def _apply_action(self): """Apply actions for policy as delta targets from current position.""" # Get current yaw for success checking. - _, _, curr_yaw = torch_utils.get_euler_xyz(self.fingertip_midpoint_quat) + _, _, curr_yaw = euler_xyz_from_quat(self.fingertip_midpoint_quat) self.curr_yaw = torch.where(curr_yaw > np.deg2rad(235), curr_yaw - 2 * np.pi, curr_yaw) # Note: We use finite-differenced velocities for control and observations. @@ -465,19 +472,19 @@ def _apply_action(self): angle = torch.norm(rot_actions, p=2, dim=-1) axis = rot_actions / angle.unsqueeze(-1) - rot_actions_quat = torch_utils.quat_from_angle_axis(angle, axis) + rot_actions_quat = quat_from_angle_axis(angle, axis) rot_actions_quat = torch.where( angle.unsqueeze(-1).repeat(1, 4) > 1e-6, rot_actions_quat, torch.tensor([0.0, 0.0, 0.0, 1.0], device=self.device).repeat(self.num_envs, 1), ) - self.ctrl_target_fingertip_midpoint_quat = torch_utils.quat_mul(rot_actions_quat, self.fingertip_midpoint_quat) + self.ctrl_target_fingertip_midpoint_quat = quat_mul(rot_actions_quat, self.fingertip_midpoint_quat) - target_euler_xyz = torch.stack(torch_utils.get_euler_xyz(self.ctrl_target_fingertip_midpoint_quat), dim=1) + target_euler_xyz = torch.stack(euler_xyz_from_quat(self.ctrl_target_fingertip_midpoint_quat), dim=1) target_euler_xyz[:, 0] = 3.14159 # Restrict actions to be upright. target_euler_xyz[:, 1] = 0.0 - self.ctrl_target_fingertip_midpoint_quat = torch_utils.quat_from_euler_xyz( + self.ctrl_target_fingertip_midpoint_quat = quat_from_euler_xyz( roll=target_euler_xyz[:, 0], pitch=target_euler_xyz[:, 1], yaw=target_euler_xyz[:, 2] ) @@ -663,18 +670,18 @@ def _set_assets_to_default_pose(self, env_ids): def _move_gripper_to_grasp_pose(self, env_ids): """Define grasp pose for plug and move gripper to pose.""" - gripper_goal_quat, gripper_goal_pos = torch_utils.tf_combine( - self.held_quat, + gripper_goal_pos, gripper_goal_quat = combine_frame_transforms( self.held_pos, - self.plug_grasp_quat_local, + self.held_quat, self.plug_grasp_pos_local, + self.plug_grasp_quat_local, ) - gripper_goal_quat, gripper_goal_pos = torch_utils.tf_combine( - gripper_goal_quat, + gripper_goal_pos, gripper_goal_quat = combine_frame_transforms( gripper_goal_pos, - self.robot_to_gripper_quat, + gripper_goal_quat, self.palm_to_finger_center, + self.robot_to_gripper_quat, ) # Set target_pos @@ -766,7 +773,7 @@ def randomize_fixed_initial_state(self, env_ids): rand_sample = torch.rand((len(env_ids), 3), dtype=torch.float32, device=self.device) fixed_orn_euler = fixed_orn_init_yaw + fixed_orn_yaw_range * rand_sample fixed_orn_euler[:, 0:2] = 0.0 # Only change yaw. - fixed_orn_quat = torch_utils.quat_from_euler_xyz( + fixed_orn_quat = quat_from_euler_xyz( fixed_orn_euler[:, 0], fixed_orn_euler[:, 1], fixed_orn_euler[:, 2] ) fixed_state[:, 3:7] = fixed_orn_quat @@ -829,8 +836,8 @@ def randomize_initial_state(self, env_ids): fixed_tip_pos_local[:, 2] += self.cfg_task.fixed_asset_cfg.height fixed_tip_pos_local[:, 2] += self.cfg_task.fixed_asset_cfg.base_height - _, fixed_tip_pos = torch_utils.tf_combine( - self.fixed_quat, self.fixed_pos, self.identity_quat, fixed_tip_pos_local + fixed_tip_pos, _ = combine_frame_transforms( + self.fixed_pos, self.fixed_quat, fixed_tip_pos_local, self.identity_quat ) self.fixed_pos_obs_frame[:] = fixed_tip_pos diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/automate/disassembly_env.py b/source/isaaclab_tasks/isaaclab_tasks/direct/automate/disassembly_env.py index 41cf740c327..1d4f6beb2b1 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/automate/disassembly_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/automate/disassembly_env.py @@ -10,14 +10,21 @@ import torch import carb -import isaacsim.core.utils.torch as torch_utils import isaaclab.sim as sim_utils from isaaclab.assets import Articulation, RigidObject from isaaclab.envs import DirectRLEnv from isaaclab.sim.spawners.from_files import GroundPlaneCfg, spawn_ground_plane from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR, retrieve_file_path -from isaaclab.utils.math import axis_angle_from_quat +from isaaclab.utils.math import ( + axis_angle_from_quat, + combine_frame_transforms, + euler_xyz_from_quat, + quat_conjugate, + quat_from_angle_axis, + quat_from_euler_xyz, + quat_mul, +) from . import automate_algo_utils as automate_algo from . import factory_control as fc @@ -215,18 +222,18 @@ def _compute_intermediate_values(self, dt): self.joint_vel = self._robot.data.joint_vel.clone() # Compute pose of gripper goal and top of socket in socket frame - self.gripper_goal_quat, self.gripper_goal_pos = torch_utils.tf_combine( - self.fixed_quat, + self.gripper_goal_pos, self.gripper_goal_quat = combine_frame_transforms( self.fixed_pos, - self.plug_grasp_quat_local, + self.fixed_quat, self.plug_grasp_pos_local, + self.plug_grasp_quat_local, ) - self.gripper_goal_quat, self.gripper_goal_pos = torch_utils.tf_combine( - self.gripper_goal_quat, + self.gripper_goal_pos, self.gripper_goal_quat = combine_frame_transforms( self.gripper_goal_pos, - self.robot_to_gripper_quat, + self.gripper_goal_quat, self.palm_to_finger_center, + self.robot_to_gripper_quat, ) # Finite-differencing results in more reliable velocity estimates. @@ -234,8 +241,8 @@ def _compute_intermediate_values(self, dt): self.prev_fingertip_pos = self.fingertip_midpoint_pos.clone() # Add state differences if velocity isn't being added. - rot_diff_quat = torch_utils.quat_mul( - self.fingertip_midpoint_quat, torch_utils.quat_conjugate(self.prev_fingertip_quat) + rot_diff_quat = quat_mul( + self.fingertip_midpoint_quat, quat_conjugate(self.prev_fingertip_quat) ) rot_diff_quat *= torch.sign(rot_diff_quat[:, 3]).unsqueeze(-1) # W component is at index 3 in XYZW format rot_diff_aa = axis_angle_from_quat(rot_diff_quat) @@ -247,11 +254,11 @@ def _compute_intermediate_values(self, dt): self.prev_joint_pos = self.joint_pos[:, 0:7].clone() # Keypoint tensors. - self.held_base_quat[:], self.held_base_pos[:] = torch_utils.tf_combine( - self.held_quat, self.held_pos, self.held_base_quat_local, self.held_base_pos_local + self.held_base_pos[:], self.held_base_quat[:] = combine_frame_transforms( + self.held_pos, self.held_quat, self.held_base_pos_local, self.held_base_quat_local ) - self.target_held_base_quat[:], self.target_held_base_pos[:] = torch_utils.tf_combine( - self.fixed_quat, self.fixed_pos, self.identity_quat, self.fixed_success_pos_local + self.target_held_base_pos[:], self.target_held_base_quat[:] = combine_frame_transforms( + self.fixed_pos, self.fixed_quat, self.fixed_success_pos_local, self.identity_quat ) self.last_update_timestamp = self._robot._data._sim_timestamp @@ -317,20 +324,20 @@ def move_gripper_in_place(self, ctrl_target_gripper_dof_pos): angle = torch.norm(rot_actions, p=2, dim=-1) axis = rot_actions / angle.unsqueeze(-1) - rot_actions_quat = torch_utils.quat_from_angle_axis(angle, axis) + rot_actions_quat = quat_from_angle_axis(angle, axis) rot_actions_quat = torch.where( angle.unsqueeze(-1).repeat(1, 4) > 1.0e-6, rot_actions_quat, torch.tensor([0.0, 0.0, 0.0, 1.0], device=self.device).repeat(self.num_envs, 1), ) - self.ctrl_target_fingertip_midpoint_quat = torch_utils.quat_mul(rot_actions_quat, self.fingertip_midpoint_quat) + self.ctrl_target_fingertip_midpoint_quat = quat_mul(rot_actions_quat, self.fingertip_midpoint_quat) - target_euler_xyz = torch.stack(torch_utils.get_euler_xyz(self.ctrl_target_fingertip_midpoint_quat), dim=1) + target_euler_xyz = torch.stack(euler_xyz_from_quat(self.ctrl_target_fingertip_midpoint_quat), dim=1) target_euler_xyz[:, 0] = 3.14159 target_euler_xyz[:, 1] = 0.0 - self.ctrl_target_fingertip_midpoint_quat = torch_utils.quat_from_euler_xyz( + self.ctrl_target_fingertip_midpoint_quat = quat_from_euler_xyz( roll=target_euler_xyz[:, 0], pitch=target_euler_xyz[:, 1], yaw=target_euler_xyz[:, 2] ) @@ -340,7 +347,7 @@ def move_gripper_in_place(self, ctrl_target_gripper_dof_pos): def _apply_action(self): """Apply actions for policy as delta targets from current position.""" # Get current yaw for success checking. - _, _, curr_yaw = torch_utils.get_euler_xyz(self.fingertip_midpoint_quat) + _, _, curr_yaw = euler_xyz_from_quat(self.fingertip_midpoint_quat) self.curr_yaw = torch.where(curr_yaw > np.deg2rad(235), curr_yaw - 2 * np.pi, curr_yaw) # Note: We use finite-differenced velocities for control and observations. @@ -369,19 +376,19 @@ def _apply_action(self): angle = torch.norm(rot_actions, p=2, dim=-1) axis = rot_actions / angle.unsqueeze(-1) - rot_actions_quat = torch_utils.quat_from_angle_axis(angle, axis) + rot_actions_quat = quat_from_angle_axis(angle, axis) rot_actions_quat = torch.where( angle.unsqueeze(-1).repeat(1, 4) > 1e-6, rot_actions_quat, torch.tensor([0.0, 0.0, 0.0, 1.0], device=self.device).repeat(self.num_envs, 1), ) - self.ctrl_target_fingertip_midpoint_quat = torch_utils.quat_mul(rot_actions_quat, self.fingertip_midpoint_quat) + self.ctrl_target_fingertip_midpoint_quat = quat_mul(rot_actions_quat, self.fingertip_midpoint_quat) - target_euler_xyz = torch.stack(torch_utils.get_euler_xyz(self.ctrl_target_fingertip_midpoint_quat), dim=1) + target_euler_xyz = torch.stack(euler_xyz_from_quat(self.ctrl_target_fingertip_midpoint_quat), dim=1) target_euler_xyz[:, 0] = 3.14159 # Restrict actions to be upright. target_euler_xyz[:, 1] = 0.0 - self.ctrl_target_fingertip_midpoint_quat = torch_utils.quat_from_euler_xyz( + self.ctrl_target_fingertip_midpoint_quat = quat_from_euler_xyz( roll=target_euler_xyz[:, 0], pitch=target_euler_xyz[:, 1], yaw=target_euler_xyz[:, 2] ) @@ -488,18 +495,18 @@ def _set_assets_to_default_pose(self, env_ids): def _move_gripper_to_grasp_pose(self, env_ids): """Define grasp pose for plug and move gripper to pose.""" - gripper_goal_quat, gripper_goal_pos = torch_utils.tf_combine( - self.held_quat, + gripper_goal_pos, gripper_goal_quat = combine_frame_transforms( self.held_pos, - self.plug_grasp_quat_local, + self.held_quat, self.plug_grasp_pos_local, + self.plug_grasp_quat_local, ) - gripper_goal_quat, gripper_goal_pos = torch_utils.tf_combine( - gripper_goal_quat, + gripper_goal_pos, gripper_goal_quat = combine_frame_transforms( gripper_goal_pos, - self.robot_to_gripper_quat, + gripper_goal_quat, self.palm_to_finger_center, + self.robot_to_gripper_quat, ) # Set target_pos @@ -633,7 +640,7 @@ def randomize_fixed_initial_state(self, env_ids): rand_sample = torch.rand((len(env_ids), 3), dtype=torch.float32, device=self.device) fixed_orn_euler = fixed_orn_init_yaw + fixed_orn_yaw_range * rand_sample fixed_orn_euler[:, 0:2] = 0.0 # Only change yaw. - fixed_orn_quat = torch_utils.quat_from_euler_xyz( + fixed_orn_quat = quat_from_euler_xyz( fixed_orn_euler[:, 0], fixed_orn_euler[:, 1], fixed_orn_euler[:, 2] ) fixed_state[:, 3:7] = fixed_orn_quat @@ -696,8 +703,8 @@ def randomize_initial_state(self, env_ids): fixed_tip_pos_local[:, 2] += self.cfg_task.fixed_asset_cfg.height fixed_tip_pos_local[:, 2] += self.cfg_task.fixed_asset_cfg.base_height - _, fixed_tip_pos = torch_utils.tf_combine( - self.fixed_quat, self.fixed_pos, self.identity_quat, fixed_tip_pos_local + fixed_tip_pos, _ = combine_frame_transforms( + self.fixed_pos, self.fixed_quat, fixed_tip_pos_local, self.identity_quat ) self.fixed_pos_obs_frame[:] = fixed_tip_pos @@ -782,7 +789,7 @@ def _randomize_gripper_pose(self, sim_steps, env_ids): torch.tensor(self.cfg_task.gripper_rand_rot_noise, device=self.device) ) ctrl_target_fingertip_centered_euler += fingertip_centered_rot_noise - ctrl_tgt_quat = torch_utils.quat_from_euler_xyz( + ctrl_tgt_quat = quat_from_euler_xyz( ctrl_target_fingertip_centered_euler[:, 0], ctrl_target_fingertip_centered_euler[:, 1], ctrl_target_fingertip_centered_euler[:, 2], diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/automate/factory_control.py b/source/isaaclab_tasks/isaaclab_tasks/direct/automate/factory_control.py index 0e51b6e41f6..885a1629f3e 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/automate/factory_control.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/automate/factory_control.py @@ -12,9 +12,7 @@ import torch -import isaacsim.core.utils.torch as torch_utils - -from isaaclab.utils.math import axis_angle_from_quat +from isaaclab.utils.math import axis_angle_from_quat, quat_conjugate, quat_mul def compute_dof_torque( @@ -116,13 +114,13 @@ def get_pose_error( quat_dot.expand(-1, 4) >= 0, ctrl_target_fingertip_midpoint_quat, -ctrl_target_fingertip_midpoint_quat ) - fingertip_midpoint_quat_norm = torch_utils.quat_mul( - fingertip_midpoint_quat, torch_utils.quat_conjugate(fingertip_midpoint_quat) - )[:, 0] # scalar component - fingertip_midpoint_quat_inv = torch_utils.quat_conjugate( + fingertip_midpoint_quat_norm = quat_mul( + fingertip_midpoint_quat, quat_conjugate(fingertip_midpoint_quat) + )[:, 3] # W component is at index 3 in XYZW format + fingertip_midpoint_quat_inv = quat_conjugate( fingertip_midpoint_quat ) / fingertip_midpoint_quat_norm.unsqueeze(-1) - quat_error = torch_utils.quat_mul(ctrl_target_fingertip_midpoint_quat, fingertip_midpoint_quat_inv) + quat_error = quat_mul(ctrl_target_fingertip_midpoint_quat, fingertip_midpoint_quat_inv) # Convert to axis-angle error axis_angle_error = axis_angle_from_quat(quat_error) diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/forge/forge_env.py b/source/isaaclab_tasks/isaaclab_tasks/direct/forge/forge_env.py index 69c4ca4d460..ac296bc597e 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/forge/forge_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/forge/forge_env.py @@ -5,9 +5,14 @@ import numpy as np import torch -import isaacsim.core.utils.torch as torch_utils - -from isaaclab.utils.math import axis_angle_from_quat +from isaaclab.utils.math import ( + axis_angle_from_quat, + euler_xyz_from_quat, + quat_conjugate, + quat_from_angle_axis, + quat_from_euler_xyz, + quat_mul, +) from isaaclab_tasks.direct.factory import factory_utils from isaaclab_tasks.direct.factory.factory_env import FactoryEnv @@ -71,8 +76,8 @@ def _compute_intermediate_values(self, dt): rot_noise_angle = torch.randn((self.num_envs,), dtype=torch.float32, device=self.device) * np.deg2rad( rot_noise_level_deg ) - self.noisy_fingertip_quat = torch_utils.quat_mul( - self.fingertip_midpoint_quat, torch_utils.quat_from_angle_axis(rot_noise_angle, rot_noise_axis) + self.noisy_fingertip_quat = quat_mul( + self.fingertip_midpoint_quat, quat_from_angle_axis(rot_noise_angle, rot_noise_axis) ) self.noisy_fingertip_quat[:, [0, 3]] = 0.0 self.noisy_fingertip_quat = self.noisy_fingertip_quat * self.flip_quats.unsqueeze(-1) @@ -82,8 +87,8 @@ def _compute_intermediate_values(self, dt): self.prev_fingertip_pos = self.noisy_fingertip_pos.clone() # Add state differences if velocity isn't being added. - rot_diff_quat = torch_utils.quat_mul( - self.noisy_fingertip_quat, torch_utils.quat_conjugate(self.prev_fingertip_quat) + rot_diff_quat = quat_mul( + self.noisy_fingertip_quat, quat_conjugate(self.prev_fingertip_quat) ) rot_diff_quat *= torch.sign(rot_diff_quat[:, 3]).unsqueeze(-1) # W component is at index 3 in XYZW format rot_diff_aa = axis_angle_from_quat(rot_diff_quat) @@ -165,16 +170,16 @@ def _apply_action(self): # Assumes joint limit is in (+x, -y)-quadrant of world frame. rot_actions[:, 2] = np.deg2rad(-180.0) + np.deg2rad(270.0) * (rot_actions[:, 2] + 1.0) / 2.0 # Joint limit. # (1.c) Get desired orientation target. - bolt_frame_quat = torch_utils.quat_from_euler_xyz( + bolt_frame_quat = quat_from_euler_xyz( roll=rot_actions[:, 0], pitch=rot_actions[:, 1], yaw=rot_actions[:, 2] ) rot_180_euler = torch.tensor([np.pi, 0.0, 0.0], device=self.device).repeat(self.num_envs, 1) - quat_bolt_to_ee = torch_utils.quat_from_euler_xyz( + quat_bolt_to_ee = quat_from_euler_xyz( roll=rot_180_euler[:, 0], pitch=rot_180_euler[:, 1], yaw=rot_180_euler[:, 2] ) - ctrl_target_fingertip_preclipped_quat = torch_utils.quat_mul(quat_bolt_to_ee, bolt_frame_quat) + ctrl_target_fingertip_preclipped_quat = quat_mul(quat_bolt_to_ee, bolt_frame_quat) # Step (2): Clip targets if they are too far from current EE pose. # (2.a): Clip position targets. @@ -187,8 +192,8 @@ def _apply_action(self): # sure we avoid the joint limit. # (2.b.i) Get current and desired Euler angles. - curr_roll, curr_pitch, curr_yaw = torch_utils.get_euler_xyz(self.fingertip_midpoint_quat) - desired_roll, desired_pitch, desired_yaw = torch_utils.get_euler_xyz(ctrl_target_fingertip_preclipped_quat) + curr_roll, curr_pitch, curr_yaw = euler_xyz_from_quat(self.fingertip_midpoint_quat) + desired_roll, desired_pitch, desired_yaw = euler_xyz_from_quat(ctrl_target_fingertip_preclipped_quat) desired_xyz = torch.stack([desired_roll, desired_pitch, desired_yaw], dim=1) # (2.b.ii) Correct the direction of motion to avoid joint limit. @@ -217,7 +222,7 @@ def _apply_action(self): clipped_pitch = torch.clip(delta_pitch, -self.rot_threshold[:, 1], self.rot_threshold[:, 1]) desired_xyz[:, 1] = curr_pitch + clipped_pitch - ctrl_target_fingertip_midpoint_quat = torch_utils.quat_from_euler_xyz( + ctrl_target_fingertip_midpoint_quat = quat_from_euler_xyz( roll=desired_xyz[:, 0], pitch=desired_xyz[:, 1], yaw=desired_xyz[:, 2] ) @@ -280,12 +285,12 @@ def _reset_idx(self, env_ids): # Relative yaw to bolt. unrot_180_euler = torch.tensor([-np.pi, 0.0, 0.0], device=self.device).repeat(self.num_envs, 1) - unrot_quat = torch_utils.quat_from_euler_xyz( + unrot_quat = quat_from_euler_xyz( roll=unrot_180_euler[:, 0], pitch=unrot_180_euler[:, 1], yaw=unrot_180_euler[:, 2] ) - fingertip_quat_rel_bolt = torch_utils.quat_mul(unrot_quat, self.fingertip_midpoint_quat) - fingertip_yaw_bolt = torch_utils.get_euler_xyz(fingertip_quat_rel_bolt)[-1] + fingertip_quat_rel_bolt = quat_mul(unrot_quat, self.fingertip_midpoint_quat) + fingertip_yaw_bolt = euler_xyz_from_quat(fingertip_quat_rel_bolt)[-1] fingertip_yaw_bolt = torch.where( fingertip_yaw_bolt > torch.pi / 2, fingertip_yaw_bolt - 2 * torch.pi, fingertip_yaw_bolt ) diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/forge/forge_utils.py b/source/isaaclab_tasks/isaaclab_tasks/direct/forge/forge_utils.py index e966cf93f21..b7bc5315170 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/forge/forge_utils.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/forge/forge_utils.py @@ -5,7 +5,7 @@ import torch -import isaacsim.core.utils.torch as torch_utils +from isaaclab.utils.math import combine_frame_transforms, quat_apply, quat_inv def get_random_prop_gains(default_values, noise_levels, num_envs, device): @@ -22,14 +22,29 @@ def get_random_prop_gains(default_values, noise_levels, num_envs, device): def change_FT_frame(source_F, source_T, source_frame, target_frame): - """Convert force/torque reading from source to target frame.""" + """Convert force/torque reading from source to target frame. + + Args: + source_F: Force in source frame. + source_T: Torque in source frame. + source_frame: Tuple of (quat_xyzw, pos) for source frame. + target_frame: Tuple of (quat_xyzw, pos) for target frame. + + Returns: + Tuple of (target_F, target_T) - force and torque in target frame. + """ # Modern Robotics eq. 3.95 - source_frame_inv = torch_utils.tf_inverse(source_frame[0], source_frame[1]) - target_T_source_quat, target_T_source_pos = torch_utils.tf_combine( - source_frame_inv[0], source_frame_inv[1], target_frame[0], target_frame[1] + # Compute inverse of source frame + source_quat_inv = quat_inv(source_frame[0]) + source_pos_inv = -quat_apply(source_quat_inv, source_frame[1]) + + # Combine: source_inv * target = target_T_source + target_T_source_pos, target_T_source_quat = combine_frame_transforms( + source_pos_inv, source_quat_inv, target_frame[1], target_frame[0] ) - target_F = torch_utils.quat_apply(target_T_source_quat, source_F) - target_T = torch_utils.quat_apply( + + target_F = quat_apply(target_T_source_quat, source_F) + target_T = quat_apply( target_T_source_quat, (source_T + torch.cross(target_T_source_pos, source_F, dim=-1)) ) return target_F, target_T 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 0e2a60ccbdf..cce01214517 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 @@ -8,7 +8,6 @@ import torch from isaaclab_physx.physics import PhysxManagerCfg -from isaacsim.core.utils.torch.transformations import tf_combine, tf_inverse, tf_vector from pxr import UsdGeom import isaaclab.sim as sim_utils @@ -21,7 +20,7 @@ from isaaclab.terrains import TerrainImporterCfg from isaaclab.utils import configclass from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR, ISAACLAB_NUCLEUS_DIR -from isaaclab.utils.math import sample_uniform +from isaaclab.utils.math import combine_frame_transforms, quat_apply, quat_inv, sample_uniform @configclass @@ -190,7 +189,8 @@ def get_env_local_pose(env_pos: torch.Tensor, xformable: UsdGeom.Xformable, devi qz = world_quat.imaginary[2] qw = world_quat.real - return torch.tensor([px, py, pz, qw, qx, qy, qz], device=device) + # Return pose as [pos(3), quat_xyzw(4)] + return torch.tensor([px, py, pz, qx, qy, qz, qw], device=device) self.dt = self.cfg.sim.dt * self.cfg.decimation @@ -223,17 +223,22 @@ 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]) + finger_pose[3:7] = lfinger_pose[3:7] # quaternion xyzw - robot_local_grasp_pose_rot, robot_local_pose_pos = tf_combine( - hand_pose_inv_rot, hand_pose_inv_pos, finger_pose[3:7], finger_pose[0:3] + # Compute inverse of hand pose: inv_q, inv_pos + hand_pose_inv_rot = quat_inv(hand_pose[3:7]) + hand_pose_inv_pos = -quat_apply(hand_pose_inv_rot, hand_pose[0:3]) + + # Combine transforms: hand_inv * finger -> local grasp pose + robot_local_pose_pos, robot_local_grasp_pose_rot = combine_frame_transforms( + hand_pose_inv_pos, hand_pose_inv_rot, finger_pose[0:3], finger_pose[3:7] ) - robot_local_pose_pos += torch.tensor([0, 0.04, 0], device=self.device) + robot_local_pose_pos = robot_local_pose_pos + torch.tensor([0, 0.04, 0], device=self.device) self.robot_local_grasp_pos = robot_local_pose_pos.repeat((self.num_envs, 1)) self.robot_local_grasp_rot = robot_local_grasp_pose_rot.repeat((self.num_envs, 1)) - drawer_local_grasp_pose = torch.tensor([0.3, 0.01, 0.0, 1.0, 0.0, 0.0, 0.0], device=self.device) + # Drawer local grasp pose: [pos(3), quat_xyzw(4)] - identity quaternion is [0,0,0,1] + drawer_local_grasp_pose = torch.tensor([0.3, 0.01, 0.0, 0.0, 0.0, 0.0, 1.0], device=self.device) self.drawer_local_grasp_pos = drawer_local_grasp_pose[0:3].repeat((self.num_envs, 1)) self.drawer_local_grasp_rot = drawer_local_grasp_pose[3:7].repeat((self.num_envs, 1)) @@ -422,10 +427,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 = quat_apply(franka_grasp_rot, gripper_forward_axis) + axis2 = quat_apply(drawer_grasp_rot, drawer_inward_axis) + axis3 = quat_apply(franka_grasp_rot, gripper_up_axis) + axis4 = quat_apply(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) @@ -486,11 +491,12 @@ def _compute_grasp_transforms( drawer_local_grasp_rot, drawer_local_grasp_pos, ): - global_franka_rot, global_franka_pos = tf_combine( - hand_rot, hand_pos, franka_local_grasp_rot, franka_local_grasp_pos + # combine_frame_transforms returns (pos, quat) + global_franka_pos, global_franka_rot = combine_frame_transforms( + hand_pos, hand_rot, franka_local_grasp_pos, franka_local_grasp_rot ) - global_drawer_rot, global_drawer_pos = tf_combine( - drawer_rot, drawer_pos, drawer_local_grasp_rot, drawer_local_grasp_pos + global_drawer_pos, global_drawer_rot = combine_frame_transforms( + drawer_pos, drawer_rot, drawer_local_grasp_pos, drawer_local_grasp_rot ) return global_franka_rot, global_franka_pos, global_drawer_rot, global_drawer_pos From 7538c656caf5aa7722e353adbbf64017a95cc272 Mon Sep 17 00:00:00 2001 From: Octi Zhang Date: Sun, 8 Feb 2026 11:38:23 -0800 Subject: [PATCH 19/46] fix stage clearance ordering issue --- .../isaaclab/isaaclab/envs/direct_marl_env.py | 10 +++------ .../isaaclab/isaaclab/envs/direct_rl_env.py | 10 +++------ .../isaaclab/envs/manager_based_env.py | 3 +++ .../isaaclab/sim/simulation_context.py | 22 +++++++++---------- .../isaaclab_physx/physics/physx_manager.py | 13 ++++++++--- 5 files changed, 30 insertions(+), 28 deletions(-) diff --git a/source/isaaclab/isaaclab/envs/direct_marl_env.py b/source/isaaclab/isaaclab/envs/direct_marl_env.py index 1664d11e258..2aefc9547b8 100644 --- a/source/isaaclab/isaaclab/envs/direct_marl_env.py +++ b/source/isaaclab/isaaclab/envs/direct_marl_env.py @@ -538,6 +538,9 @@ def render(self, recompute: bool = False) -> np.ndarray | None: def close(self): """Cleanup for the environment.""" if not self._is_closed: + # Stop simulation first to allow physics to clean up properly + self.sim.stop() + # close entities related to the environment # note: this is order-sensitive to avoid any dangling references if self.cfg.events: @@ -546,13 +549,6 @@ def close(self): if self.viewport_camera_controller is not None: del self.viewport_camera_controller - # clear callbacks and instance - if get_isaac_sim_version().major >= 5: - if self.cfg.sim.create_stage_in_memory: - # detach physx stage - omni.physx.get_physx_simulation_interface().detach_stage() - self.sim.stop() - self.sim.clear_instance() # destroy the window diff --git a/source/isaaclab/isaaclab/envs/direct_rl_env.py b/source/isaaclab/isaaclab/envs/direct_rl_env.py index f3595939b14..1abe3127651 100644 --- a/source/isaaclab/isaaclab/envs/direct_rl_env.py +++ b/source/isaaclab/isaaclab/envs/direct_rl_env.py @@ -511,6 +511,9 @@ def render(self, recompute: bool = False) -> np.ndarray | None: def close(self): """Cleanup for the environment.""" if not self._is_closed: + # Stop simulation first to allow physics to clean up properly + self.sim.stop() + # close entities related to the environment # note: this is order-sensitive to avoid any dangling references if self.cfg.events: @@ -519,13 +522,6 @@ def close(self): if self.viewport_camera_controller is not None: del self.viewport_camera_controller - # clear callbacks and instance - if get_isaac_sim_version().major >= 5: - if self.cfg.sim.create_stage_in_memory: - # detach physx stage - omni.physx.get_physx_simulation_interface().detach_stage() - self.sim.stop() - self.sim.clear_instance() # destroy the window diff --git a/source/isaaclab/isaaclab/envs/manager_based_env.py b/source/isaaclab/isaaclab/envs/manager_based_env.py index 33128bd4123..cdef1da696a 100644 --- a/source/isaaclab/isaaclab/envs/manager_based_env.py +++ b/source/isaaclab/isaaclab/envs/manager_based_env.py @@ -525,6 +525,9 @@ def seed(seed: int = -1) -> int: def close(self): """Cleanup for the environment.""" if not self._is_closed: + # Stop simulation first to allow physics to clean up properly + self.sim.stop() + # destructor is order-sensitive del self.viewport_camera_controller del self.action_manager diff --git a/source/isaaclab/isaaclab/sim/simulation_context.py b/source/isaaclab/isaaclab/sim/simulation_context.py index 3801cce25cb..7605f8fd58b 100644 --- a/source/isaaclab/isaaclab/sim/simulation_context.py +++ b/source/isaaclab/isaaclab/sim/simulation_context.py @@ -302,12 +302,13 @@ def get_setting(self, name: str) -> Any: def clear_instance(cls) -> None: """Clean up resources and clear the singleton instance.""" if cls._instance is not None: - # Clear stage contents first - cls.clear_stage() - - # Close physics manager + # Close physics manager FIRST to detach PhysX from the stage + # This must happen before clearing USD prims to avoid PhysX cleanup errors cls._instance.physics_manager.close() + # Now safe to clear stage contents (PhysX is detached) + cls.clear_stage() + # Close all visualizers for viz in cls._instance._visualizers: viz.close() @@ -331,15 +332,14 @@ def clear_instance(cls) -> None: @classmethod def clear_stage(cls) -> None: - """Clear the current USD stage (preserving /World and PhysicsScene).""" + """Clear the current USD stage. + + Uses the default predicate which skips root, /Render, no_delete prims, + hidden prims, and ancestral prims (from USD references). + """ if cls._instance is None: return - - def _predicate(prim: Usd.Prim) -> bool: - path = prim.GetPath().pathString # type: ignore[union-attr] - return path != "/World" and prim.GetTypeName() != "PhysicsScene" - - sim_utils.clear_stage(predicate=_predicate) + sim_utils.clear_stage() @contextmanager diff --git a/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py b/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py index b105ab70662..47a51be8941 100644 --- a/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py +++ b/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py @@ -284,12 +284,19 @@ def stop(cls) -> None: @classmethod def close(cls) -> None: """Clean up physics resources.""" - cls._event_bus.dispatch_event(IsaacEvents.PRIM_DELETION.value, payload={"prim_path": "/"}) + # Detach PhysX from the stage FIRST to prevent shape/actor cleanup errors + # This disconnects PhysX from USD before any deletion events are fired + if cls._physx_sim is not None: + cls._physx_sim.detach_stage() + # Pump the app to flush pending PhysX cleanup operations + omni.kit.app.get_app().update() + + # Now invalidate views (they're already disconnected from PhysX) cls._invalidate_views() cls._subscriptions.clear() - if cls._physx_sim is not None: - cls._physx_sim.detach_stage() + # Notify listeners that prims are being deleted (safe now since PhysX is detached) + cls._event_bus.dispatch_event(IsaacEvents.PRIM_DELETION.value, payload={"prim_path": "/"}) cls._fabric = None cls._update_fabric = None From f2116eb4fdc46e4b933aa4296ab5f6093b55cb2c Mon Sep 17 00:00:00 2001 From: Octi Zhang Date: Sun, 8 Feb 2026 11:44:20 -0800 Subject: [PATCH 20/46] fix prim delete predicate --- .../isaaclab/sim/simulation_context.py | 17 ++++-- source/isaaclab/isaaclab/sim/utils/stage.py | 55 ++++++++++++------- 2 files changed, 47 insertions(+), 25 deletions(-) diff --git a/source/isaaclab/isaaclab/sim/simulation_context.py b/source/isaaclab/isaaclab/sim/simulation_context.py index 7605f8fd58b..c74f967b02d 100644 --- a/source/isaaclab/isaaclab/sim/simulation_context.py +++ b/source/isaaclab/isaaclab/sim/simulation_context.py @@ -332,14 +332,23 @@ def clear_instance(cls) -> None: @classmethod def clear_stage(cls) -> None: - """Clear the current USD stage. + """Clear the current USD stage (preserving /World and PhysicsScene). - Uses the default predicate which skips root, /Render, no_delete prims, - hidden prims, and ancestral prims (from USD references). + Uses a predicate that preserves /World and PhysicsScene while also + respecting the default deletability checks (ancestral prims, etc.). """ if cls._instance is None: return - sim_utils.clear_stage() + + def _predicate(prim: Usd.Prim) -> bool: + path = prim.GetPath().pathString + if path == "/World": + return False + if prim.GetTypeName() == "PhysicsScene": + return False + return True + + sim_utils.clear_stage(predicate=_predicate) @contextmanager diff --git a/source/isaaclab/isaaclab/sim/utils/stage.py b/source/isaaclab/isaaclab/sim/utils/stage.py index 042063ee2c1..2b22ed5654b 100644 --- a/source/isaaclab/isaaclab/sim/utils/stage.py +++ b/source/isaaclab/isaaclab/sim/utils/stage.py @@ -288,6 +288,36 @@ def close_stage(callback_fn: Callable[[bool, str], None] | None = None) -> bool: return result +def is_prim_deletable(prim: Usd.Prim) -> bool: + """Check if a prim can be safely deleted. + + This function checks various conditions to determine if a prim should be deleted: + - Root prim ("/") cannot be deleted + - Prims under "/Render" namespace are preserved + - Prims with "no_delete" metadata are preserved + - Prims hidden in stage window are preserved + - Ancestral prims (from USD references) cannot be deleted + + Args: + prim: The USD prim to check. + + Returns: + True if the prim can be deleted, False otherwise. + """ + prim_path = prim.GetPath().pathString + if prim_path == "/": + return False + if prim_path.startswith("/Render"): + return False + if prim.GetMetadata("no_delete"): + return False + if prim.GetMetadata("hide_in_stage_window"): + return False + if omni.usd.check_ancestral(prim): + return False + return True + + def clear_stage(predicate: Callable[[Usd.Prim], bool] | None = None) -> None: """Deletes all prims in the stage without populating the undo command buffer. @@ -316,31 +346,14 @@ def clear_stage(predicate: Callable[[Usd.Prim], bool] | None = None) -> None: from .prims import delete_prim from .queries import get_all_matching_child_prims - def _default_predicate(prim: Usd.Prim) -> bool: - """Check if the prim should be deleted.""" - prim_path = prim.GetPath().pathString - if prim_path == "/": - return False - if prim_path.startswith("/Render"): - return False - if prim.GetMetadata("no_delete"): - return False - if prim.GetMetadata("hide_in_stage_window"): - return False - 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) + return is_prim_deletable(prim) + # Custom predicate must also pass the deletable check + return predicate(prim) and is_prim_deletable(prim) # get all prims to delete - if predicate is None: - prims = get_all_matching_child_prims("/", _default_predicate) - else: - prims = get_all_matching_child_prims("/", _predicate_from_path) + prims = get_all_matching_child_prims("/", _predicate_from_path) # convert prims to prim paths prim_paths_to_delete = [prim.GetPath().pathString for prim in prims] # delete prims From db67a3581f5dec0d9d26b890ab95e831195dbd68 Mon Sep 17 00:00:00 2001 From: Octi Zhang Date: Sun, 8 Feb 2026 11:58:45 -0800 Subject: [PATCH 21/46] fix drop down logic --- .../isaaclab/envs/ui/base_env_window.py | 35 +++++++++++++++++-- .../test/envs/test_env_rendering_logic.py | 6 ++-- 2 files changed, 37 insertions(+), 4 deletions(-) diff --git a/source/isaaclab/isaaclab/envs/ui/base_env_window.py b/source/isaaclab/isaaclab/envs/ui/base_env_window.py index e3b071054f2..52978453bf1 100644 --- a/source/isaaclab/isaaclab/envs/ui/base_env_window.py +++ b/source/isaaclab/isaaclab/envs/ui/base_env_window.py @@ -123,8 +123,8 @@ def _build_sim_frame(self): # create stack for controls self.ui_window_elements["sim_vstack"] = omni.ui.VStack(spacing=5, height=0) with self.ui_window_elements["sim_vstack"]: - # Note: Rendering mode dropdown removed - rendering is now managed through visualizer config - pass + # create rendering mode dropdown if visualizer supports it + self._build_render_mode_dropdown() # create animation recording box record_animate_cfg = { @@ -143,6 +143,37 @@ def _build_sim_frame(self): "/isaaclab/fabric_enabled" ) + def _build_render_mode_dropdown(self): + """Build rendering mode dropdown if a visualizer supports it.""" + # Find first visualizer with render_mode support + viz = None + RenderMode = None + for v in self.env.sim.visualizers: + if hasattr(v, "render_mode") and hasattr(v, "set_render_mode"): + viz = v + # Get RenderMode enum from the visualizer's module + RenderMode = type(v.render_mode) + break + + if viz is None or RenderMode is None: + return + + def on_render_mode_changed(value: str): + if viz is not None and hasattr(viz, "set_render_mode"): + viz.set_render_mode(RenderMode[value]) + + render_mode_cfg = { + "label": "Rendering Mode", + "type": "dropdown", + "default_val": viz.render_mode.value, + "items": [member.name for member in RenderMode if member.value >= 0], + "tooltip": "Select a rendering mode\n" + (RenderMode.__doc__ or ""), + "on_clicked_fn": on_render_mode_changed, + } + self.ui_window_elements["render_dropdown"] = ( + isaacsim.gui.components.ui_utils.dropdown_builder(**render_mode_cfg) + ) + def _build_viewer_frame(self): """Build the viewer-related control frame for the UI.""" # create collapsable frame for viewer diff --git a/source/isaaclab/test/envs/test_env_rendering_logic.py b/source/isaaclab/test/envs/test_env_rendering_logic.py index ce39c5ab76a..6cc11e8505b 100644 --- a/source/isaaclab/test/envs/test_env_rendering_logic.py +++ b/source/isaaclab/test/envs/test_env_rendering_logic.py @@ -16,6 +16,7 @@ import pytest import torch from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.visualizers import RenderMode import omni.usd @@ -28,7 +29,7 @@ ManagerBasedRLEnvCfg, ) from isaaclab.scene import InteractiveSceneCfg -from isaaclab.sim import SimulationCfg, SimulationContext +from isaaclab.sim import SimulationCfg from isaaclab.utils import configclass @@ -181,7 +182,8 @@ def test_env_rendering_logic(env_type, render_interval, physics_callback, render # check that we are in partial rendering mode for the environment # this is enabled due to app launcher setting "enable_cameras=True" - assert env.sim.render_mode == SimulationContext.RenderMode.PARTIAL_RENDERING + # Access render mode through the first visualizer (OVVisualizer) + assert env.sim.visualizers[0].render_mode == RenderMode.PARTIAL_RENDERING # add physics and render callbacks env.sim.add_physics_callback("physics_step", physics_cb) From 477008ea78445a5ecb2ce3c1bd0ee40475451267 Mon Sep 17 00:00:00 2001 From: Octi Zhang Date: Sun, 8 Feb 2026 12:12:38 -0800 Subject: [PATCH 22/46] simplified the rendering mode query --- .../isaaclab/isaaclab/envs/direct_marl_env.py | 18 +++++------- .../isaaclab/isaaclab/envs/direct_rl_env.py | 27 +++++++---------- .../isaaclab/envs/manager_based_env.py | 16 +++++----- .../isaaclab/envs/manager_based_rl_env.py | 19 ++++-------- .../isaaclab/sim/simulation_context.py | 29 +++++++++++++++++-- source/isaaclab/isaaclab/sim/utils/stage.py | 2 +- .../test/sim/test_simulation_context.py | 10 +++---- .../isaaclab_physx/physics/physx_manager.py | 6 ++-- .../visualizers/ov_visualizer.py | 12 ++++---- .../direct/automate/disassembly_env.py | 2 +- 10 files changed, 72 insertions(+), 69 deletions(-) diff --git a/source/isaaclab/isaaclab/envs/direct_marl_env.py b/source/isaaclab/isaaclab/envs/direct_marl_env.py index 2aefc9547b8..b2975945ee6 100644 --- a/source/isaaclab/isaaclab/envs/direct_marl_env.py +++ b/source/isaaclab/isaaclab/envs/direct_marl_env.py @@ -133,7 +133,7 @@ def __init__(self, cfg: DirectMARLEnvCfg, render_mode: str | None = None, **kwar # viewport is not available in other rendering modes so the function will throw a warning # FIXME: This needs to be fixed in the future when we unify the UI functionalities even for # non-rendering modes. - if self.sim.carb_settings.get("/isaaclab/has_gui"): + if self.sim.has_gui: self.viewport_camera_controller = ViewportCameraController(self, self.cfg.viewer) else: self.viewport_camera_controller = None @@ -172,7 +172,7 @@ def __init__(self, cfg: DirectMARLEnvCfg, render_mode: str | None = None, **kwar # extend UI elements # we need to do this here after all the managers are initialized # this is because they dictate the sensors and commands right now - if self.sim.carb_settings.get("/isaaclab/has_gui") and self.cfg.ui_window_class_type is not None: + if self.sim.has_gui and self.cfg.ui_window_class_type is not None: self._window = self.cfg.ui_window_class_type(self, window_name="IsaacLab") else: # if no window, then we don't need to store the window @@ -374,10 +374,8 @@ def step(self, actions: dict[AgentID, ActionType]) -> EnvStepReturn: self._pre_physics_step(actions) # check if we need to do rendering within the physics loop - # note: checked here once to avoid multiple checks within the loop - is_rendering = self.sim.carb_settings.get("/isaaclab/has_gui") or self.sim.carb_settings.get_as_bool( - "/isaaclab/render/rtx_sensors" - ) + # note: uses cached property to avoid settings lookup every step + is_rendering = self.sim.is_rendering # perform physics stepping for _ in range(self.cfg.decimation): @@ -494,17 +492,15 @@ def render(self, recompute: bool = False) -> np.ndarray | None: NotImplementedError: If an unsupported rendering mode is specified. """ # run a rendering step of the simulator - # if we have rtx sensors, we do not need to render again sin - if not self.sim.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") and not recompute: + # if we have rtx sensors, we do not need to render again since step already rendered + if not self.sim.has_rtx_sensors and not recompute: self.sim.render() # decide the rendering mode if self.render_mode == "human" or self.render_mode is None: return None elif self.render_mode == "rgb_array": # check that if any render could have happened - if not self.sim.carb_settings.get("/isaaclab/has_gui") and not bool( - self.sim.carb_settings.get("/isaaclab/render/offscreen") - ): + if not self.sim.has_gui and not self.sim.has_offscreen_render: raise RuntimeError( f"Cannot render '{self.render_mode}' - no GUI and offscreen rendering not enabled." " If running headless, make sure --enable_cameras is set." diff --git a/source/isaaclab/isaaclab/envs/direct_rl_env.py b/source/isaaclab/isaaclab/envs/direct_rl_env.py index 1abe3127651..f88fb20931b 100644 --- a/source/isaaclab/isaaclab/envs/direct_rl_env.py +++ b/source/isaaclab/isaaclab/envs/direct_rl_env.py @@ -139,7 +139,7 @@ def __init__(self, cfg: DirectRLEnvCfg, render_mode: str | None = None, **kwargs # viewport is not available in other rendering modes so the function will throw a warning # FIXME: This needs to be fixed in the future when we unify the UI functionalities even for # non-rendering modes. - if self.sim.carb_settings.get("/isaaclab/has_gui"): + if self.sim.has_gui: self.viewport_camera_controller = ViewportCameraController(self, self.cfg.viewer) else: self.viewport_camera_controller = None @@ -178,7 +178,7 @@ def __init__(self, cfg: DirectRLEnvCfg, render_mode: str | None = None, **kwargs # extend UI elements # we need to do this here after all the managers are initialized # this is because they dictate the sensors and commands right now - if self.sim.carb_settings.get("/isaaclab/has_gui") and self.cfg.ui_window_class_type is not None: + if self.sim.has_gui and self.cfg.ui_window_class_type is not None: self._window = self.cfg.ui_window_class_type(self, window_name="IsaacLab") else: # if no window, then we don't need to store the window @@ -318,11 +318,11 @@ def reset(self, seed: int | None = None, options: dict[str, Any] | None = None) self.sim.forward() # if sensors are added to the scene, make sure we render to reflect changes in reset - if self.sim.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") and self.cfg.num_rerenders_on_reset > 0: + if self.sim.has_rtx_sensors and self.cfg.num_rerenders_on_reset > 0: for _ in range(self.cfg.num_rerenders_on_reset): self.sim.render() - if self.cfg.wait_for_textures and self.sim.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors"): + if self.cfg.wait_for_textures and self.sim.has_rtx_sensors: # Wait for assets to finish loading (PhysX-specific) pm = self.sim.physics_manager if hasattr(pm, "assets_loading"): @@ -365,10 +365,8 @@ def step(self, action: torch.Tensor) -> VecEnvStepReturn: self._pre_physics_step(action) # check if we need to do rendering within the physics loop - # note: checked here once to avoid multiple checks within the loop - is_rendering = self.sim.carb_settings.get("/isaaclab/has_gui") or self.sim.carb_settings.get_as_bool( - "/isaaclab/render/rtx_sensors" - ) + # note: uses cached property to avoid settings lookup every step + is_rendering = self.sim.is_rendering # perform physics stepping for _ in range(self.cfg.decimation): @@ -401,10 +399,7 @@ def step(self, action: torch.Tensor) -> VecEnvStepReturn: if len(reset_env_ids) > 0: self._reset_idx(reset_env_ids) # if sensors are added to the scene, make sure we render to reflect changes in reset - if ( - self.sim.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") - and self.cfg.num_rerenders_on_reset > 0 - ): + if self.sim.has_rtx_sensors and self.cfg.num_rerenders_on_reset > 0: for _ in range(self.cfg.num_rerenders_on_reset): self.sim.render() @@ -467,17 +462,15 @@ def render(self, recompute: bool = False) -> np.ndarray | None: NotImplementedError: If an unsupported rendering mode is specified. """ # run a rendering step of the simulator - # if we have rtx sensors, we do not need to render again sin - if not self.sim.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") and not recompute: + # if we have rtx sensors, we do not need to render again since step already rendered + if not self.sim.has_rtx_sensors and not recompute: self.sim.render() # decide the rendering mode if self.render_mode == "human" or self.render_mode is None: return None elif self.render_mode == "rgb_array": # check that if any render could have happened - if not self.sim.carb_settings.get("/isaaclab/has_gui") and not bool( - self.sim.carb_settings.get("/isaaclab/render/offscreen") - ): + if not self.sim.has_gui and not self.sim.has_offscreen_render: raise RuntimeError( f"Cannot render '{self.render_mode}' - no GUI and offscreen rendering not enabled." " If running headless, make sure --enable_cameras is set." diff --git a/source/isaaclab/isaaclab/envs/manager_based_env.py b/source/isaaclab/isaaclab/envs/manager_based_env.py index cdef1da696a..80af872f364 100644 --- a/source/isaaclab/isaaclab/envs/manager_based_env.py +++ b/source/isaaclab/isaaclab/envs/manager_based_env.py @@ -143,7 +143,7 @@ def __init__(self, cfg: ManagerBasedEnvCfg): # viewport is not available in other rendering modes so the function will throw a warning # FIXME: This needs to be fixed in the future when we unify the UI functionalities even for # non-rendering modes. - if self.sim.carb_settings.get("/isaaclab/has_gui"): + if self.sim.has_gui: self.viewport_camera_controller = ViewportCameraController(self, self.cfg.viewer) else: self.viewport_camera_controller = None @@ -178,7 +178,7 @@ def __init__(self, cfg: ManagerBasedEnvCfg): # extend UI elements # we need to do this here after all the managers are initialized # this is because they dictate the sensors and commands right now - if self.sim.carb_settings.get("/isaaclab/has_gui") and self.cfg.ui_window_class_type is not None: + if self.sim.has_gui and self.cfg.ui_window_class_type is not None: # setup live visualizers self.setup_manager_visualizers() self._window = self.cfg.ui_window_class_type(self, window_name="IsaacLab") @@ -371,7 +371,7 @@ def reset( self.scene.write_data_to_sim() self.sim.forward() # if sensors are added to the scene, make sure we render to reflect changes in reset - if self.sim.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") and self.cfg.num_rerenders_on_reset > 0: + if self.sim.has_rtx_sensors and self.cfg.num_rerenders_on_reset > 0: for _ in range(self.cfg.num_rerenders_on_reset): self.sim.render() @@ -381,7 +381,7 @@ def reset( # compute observations self.obs_buf = self.observation_manager.compute(update_history=True) - if self.cfg.wait_for_textures and self.sim.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors"): + if self.cfg.wait_for_textures and self.sim.has_rtx_sensors: # Wait for assets to finish loading (PhysX-specific) pm = self.sim.physics_manager if hasattr(pm, "assets_loading"): @@ -435,7 +435,7 @@ def reset_to( self.sim.forward() # if sensors are added to the scene, make sure we render to reflect changes in reset - if self.sim.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") and self.cfg.num_rerenders_on_reset > 0: + if self.sim.has_rtx_sensors and self.cfg.num_rerenders_on_reset > 0: for _ in range(self.cfg.num_rerenders_on_reset): self.sim.render() @@ -469,10 +469,8 @@ def step(self, action: torch.Tensor) -> tuple[VecEnvObs, dict]: self.recorder_manager.record_pre_step() # check if we need to do rendering within the physics loop - # note: checked here once to avoid multiple checks within the loop - is_rendering = self.sim.carb_settings.get("/isaaclab/has_gui") or self.sim.carb_settings.get_as_bool( - "/isaaclab/render/rtx_sensors" - ) + # note: uses cached property to avoid settings lookup every step + is_rendering = self.sim.is_rendering # perform physics stepping for _ in range(self.cfg.decimation): diff --git a/source/isaaclab/isaaclab/envs/manager_based_rl_env.py b/source/isaaclab/isaaclab/envs/manager_based_rl_env.py index 86ad11a104c..02e25373ab3 100644 --- a/source/isaaclab/isaaclab/envs/manager_based_rl_env.py +++ b/source/isaaclab/isaaclab/envs/manager_based_rl_env.py @@ -175,10 +175,8 @@ def step(self, action: torch.Tensor) -> VecEnvStepReturn: self.recorder_manager.record_pre_step() # check if we need to do rendering within the physics loop - # note: checked here once to avoid multiple checks within the loop - is_rendering = self.sim.carb_settings.get("/isaaclab/has_gui") or self.sim.carb_settings.get_as_bool( - "/isaaclab/render/rtx_sensors" - ) + # note: uses cached property to avoid settings lookup every step + is_rendering = self.sim.is_rendering # perform physics stepping for _ in range(self.cfg.decimation): @@ -223,10 +221,7 @@ def step(self, action: torch.Tensor) -> VecEnvStepReturn: self._reset_idx(reset_env_ids) # if sensors are added to the scene, make sure we render to reflect changes in reset - if ( - self.sim.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") - and self.cfg.num_rerenders_on_reset > 0 - ): + if self.sim.has_rtx_sensors and self.cfg.num_rerenders_on_reset > 0: for _ in range(self.cfg.num_rerenders_on_reset): self.sim.render() @@ -268,17 +263,15 @@ def render(self, recompute: bool = False) -> np.ndarray | None: NotImplementedError: If an unsupported rendering mode is specified. """ # run a rendering step of the simulator - # if we have rtx sensors, we do not need to render again sin - if not self.sim.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") and not recompute: + # if we have rtx sensors, we do not need to render again since step already rendered + if not self.sim.has_rtx_sensors and not recompute: self.sim.render() # decide the rendering mode if self.render_mode == "human" or self.render_mode is None: return None elif self.render_mode == "rgb_array": # check that if any render could have happened - if not self.sim.carb_settings.get("/isaaclab/has_gui") and not bool( - self.sim.carb_settings.get("/isaaclab/render/offscreen") - ): + if not self.sim.has_gui and not self.sim.has_offscreen_render: raise RuntimeError( f"Cannot render '{self.render_mode}' - no GUI and offscreen rendering not enabled." " If running headless, make sure --enable_cameras is set." diff --git a/source/isaaclab/isaaclab/sim/simulation_context.py b/source/isaaclab/isaaclab/sim/simulation_context.py index c74f967b02d..72ed1904774 100644 --- a/source/isaaclab/isaaclab/sim/simulation_context.py +++ b/source/isaaclab/isaaclab/sim/simulation_context.py @@ -106,8 +106,8 @@ def __init__(self, cfg: SimulationCfg | None = None): stage_utils._context.stage = self.stage # Acquire settings interface and create helper - self.carb_settings = carb.settings.get_settings() - self._settings_helper = SettingsHelper(self.carb_settings) + self._carb_settings = carb.settings.get_settings() + self._settings_helper = SettingsHelper(self._carb_settings) # Initialize USD physics scene and physics manager self._init_usd_physics_scene() @@ -118,6 +118,11 @@ def __init__(self, cfg: SimulationCfg | None = None): # Initialize visualizers self._init_visualizers() + # Cache commonly-used settings (these don't change during runtime) + self._has_gui = bool(self.get_setting("/isaaclab/has_gui")) + self._has_rtx_sensors = bool(self.get_setting("/isaaclab/render/rtx_sensors")) + self._has_offscreen_render = bool(self.get_setting("/isaaclab/render/offscreen")) + # Simulation state self._is_playing = False self._is_stopped = True @@ -170,6 +175,26 @@ def backend(self) -> str: """Returns the tensor backend being used ("numpy" or "torch").""" return self.physics_manager.get_backend() + @property + def has_gui(self) -> bool: + """Returns whether GUI is enabled (cached at init).""" + return self._has_gui + + @property + def has_rtx_sensors(self) -> bool: + """Returns whether RTX sensors are enabled (cached at init).""" + return self._has_rtx_sensors + + @property + def has_offscreen_render(self) -> bool: + """Returns whether offscreen rendering is enabled (cached at init).""" + return self._has_offscreen_render + + @property + def is_rendering(self) -> bool: + """Returns whether rendering is active (GUI or RTX sensors).""" + return self._has_gui or self._has_rtx_sensors + def get_physics_dt(self) -> float: """Returns the physics time step.""" return self.physics_manager.get_physics_dt() diff --git a/source/isaaclab/isaaclab/sim/utils/stage.py b/source/isaaclab/isaaclab/sim/utils/stage.py index 2b22ed5654b..3ec85448e61 100644 --- a/source/isaaclab/isaaclab/sim/utils/stage.py +++ b/source/isaaclab/isaaclab/sim/utils/stage.py @@ -485,5 +485,5 @@ def attach_stage_to_usd_context(attaching_early: bool = False): ) # Enable physics fabric and attach stage to usd context for rendering - SimulationContext.instance().carb_settings.set_bool("/isaaclab/fabric_enabled", True) + SimulationContext.instance().set_setting("/isaaclab/fabric_enabled", True) omni.usd.get_context().attach_stage_with_callback(stage_id) diff --git a/source/isaaclab/test/sim/test_simulation_context.py b/source/isaaclab/test/sim/test_simulation_context.py index a315ab2a0c6..d8d45c21647 100644 --- a/source/isaaclab/test/sim/test_simulation_context.py +++ b/source/isaaclab/test/sim/test_simulation_context.py @@ -64,7 +64,7 @@ def test_init(device): # verify device property assert sim.device == device # verify no RTX sensors are available - assert not sim.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") + assert not sim.has_rtx_sensors # obtain physics scene from USD from pxr import UsdPhysics @@ -141,10 +141,8 @@ def test_carb_setting(): def test_headless_mode(): """Test that render mode is headless since we are running in headless mode.""" sim = SimulationContext() - # check default render mode - assert not sim.carb_settings.get("/isaaclab/has_gui") and not bool( - sim.carb_settings.get("/isaaclab/render/offscreen") - ) + # check default render mode (no GUI and no offscreen rendering) + assert not sim.has_gui and not sim.has_offscreen_render """ @@ -368,7 +366,7 @@ def test_fabric_setting(use_fabric): sim = SimulationContext(cfg) # check fabric is enabled via physics setting - assert sim.carb_settings.get_as_bool("/isaaclab/fabric_enabled") == use_fabric + assert sim.get_setting("/isaaclab/fabric_enabled") == use_fabric @pytest.mark.isaacsim_ci diff --git a/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py b/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py index 47a51be8941..9c51eae2904 100644 --- a/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py +++ b/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py @@ -207,7 +207,7 @@ def initialize(cls, sim_context: SimulationContext) -> None: cls._setup_subscriptions() cls._configure_physics() cls._load_fabric() - cls._anim_recorder = AnimationRecorder(sim_context.carb_settings) + cls._anim_recorder = AnimationRecorder(sim_context._carb_settings) # force update cycle to apply dt sim = PhysicsManager._sim @@ -431,7 +431,7 @@ def _configure_physics(cls) -> None: if sim is None or cfg is None: return - settings = sim.carb_settings + settings = sim._carb_settings device = sim.device # global carb settings @@ -522,7 +522,7 @@ def _load_fabric(cls) -> None: if sim is None or cfg is None: return - settings = sim.carb_settings + settings = sim._carb_settings use_fabric = cfg.use_fabric ext_mgr = omni.kit.app.get_app().get_extension_manager() diff --git a/source/isaaclab_physx/isaaclab_physx/visualizers/ov_visualizer.py b/source/isaaclab_physx/isaaclab_physx/visualizers/ov_visualizer.py index 4be60f16b56..15f4263bfa1 100644 --- a/source/isaaclab_physx/isaaclab_physx/visualizers/ov_visualizer.py +++ b/source/isaaclab_physx/isaaclab_physx/visualizers/ov_visualizer.py @@ -135,11 +135,11 @@ def initialize(self, scene_data: dict[str, Any] | None = None) -> None: self._app_iface = omni.kit.app.get_app_interface() # Detect render flags from carb settings - local_gui = self._sim.carb_settings.get("/app/window/enabled") - livestream_gui = self._sim.carb_settings.get("/app/livestream/enabled") - xr_gui = self._sim.carb_settings.get("/app/xr/enabled") - self._offscreen_render = bool(self._sim.carb_settings.get("/isaaclab/render/offscreen")) - self._render_viewport = bool(self._sim.carb_settings.get("/isaaclab/render/active_viewport")) + local_gui = self._sim.get_setting("/app/window/enabled") + livestream_gui = self._sim.get_setting("/app/livestream/enabled") + xr_gui = self._sim.get_setting("/app/xr/enabled") + self._offscreen_render = bool(self._sim.get_setting("/isaaclab/render/offscreen")) + self._render_viewport = bool(self._sim.get_setting("/isaaclab/render/active_viewport")) # Flag for whether any GUI will be rendered self._has_gui = bool(local_gui or livestream_gui or xr_gui) @@ -265,7 +265,7 @@ def get_rendering_dt(self) -> float | None: if self._sim is None: return None - settings = self._sim.carb_settings + settings = self._sim._carb_settings def _from_frequency(): freq = settings.get("/app/runLoops/main/rateLimitFrequency") diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/automate/disassembly_env.py b/source/isaaclab_tasks/isaaclab_tasks/direct/automate/disassembly_env.py index 1d4f6beb2b1..59d6ee8b648 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/automate/disassembly_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/automate/disassembly_env.py @@ -575,7 +575,7 @@ def _move_gripper_to_eef_pose(self, env_ids, goal_pos, goal_quat, sim_steps, if_ self.actions *= 0.0 self.actions[env_ids, :6] = delta_hand_pose - is_rendering = self.sim.carb_settings.get("/isaaclab/has_gui") or self.sim.has_rtx_sensors() + is_rendering = self.sim.is_rendering # perform physics stepping for _ in range(self.cfg.decimation): self._sim_step_counter += 1 From 88185a879e9553f67f4cb2a765e53b7107b1260e Mon Sep 17 00:00:00 2001 From: Octi Zhang Date: Sun, 8 Feb 2026 12:13:22 -0800 Subject: [PATCH 23/46] pass precommit --- .../isaaclab/isaaclab/envs/direct_marl_env.py | 1 - source/isaaclab/isaaclab/envs/direct_rl_env.py | 1 - .../isaaclab/envs/ui/base_env_window.py | 4 ++-- .../test/controllers/test_operational_space.py | 2 +- .../isaaclab/test/sim/test_mjcf_converter.py | 2 +- source/isaaclab/test/sim/test_spawn_meshes.py | 2 +- source/isaaclab/test/sim/test_spawn_sensors.py | 2 +- .../tacsl_sensor/visuotactile_sensor.py | 4 ++-- .../direct/automate/assembly_env.py | 18 +++++++----------- .../direct/automate/disassembly_env.py | 8 ++------ .../direct/automate/factory_control.py | 12 ++++++------ .../isaaclab_tasks/direct/forge/forge_env.py | 8 ++------ .../isaaclab_tasks/direct/forge/forge_utils.py | 4 +--- 13 files changed, 26 insertions(+), 42 deletions(-) diff --git a/source/isaaclab/isaaclab/envs/direct_marl_env.py b/source/isaaclab/isaaclab/envs/direct_marl_env.py index b2975945ee6..381a0dc45e7 100644 --- a/source/isaaclab/isaaclab/envs/direct_marl_env.py +++ b/source/isaaclab/isaaclab/envs/direct_marl_env.py @@ -29,7 +29,6 @@ from isaaclab.utils.noise import NoiseModel from isaaclab.utils.seed import configure_seed from isaaclab.utils.timer import Timer -from isaaclab.utils.version import get_isaac_sim_version from .common import ActionType, AgentID, EnvStepReturn, ObsType, StateType from .direct_marl_env_cfg import DirectMARLEnvCfg diff --git a/source/isaaclab/isaaclab/envs/direct_rl_env.py b/source/isaaclab/isaaclab/envs/direct_rl_env.py index f88fb20931b..f9c141b4fe4 100644 --- a/source/isaaclab/isaaclab/envs/direct_rl_env.py +++ b/source/isaaclab/isaaclab/envs/direct_rl_env.py @@ -30,7 +30,6 @@ from isaaclab.utils.noise import NoiseModel from isaaclab.utils.seed import configure_seed from isaaclab.utils.timer import Timer -from isaaclab.utils.version import get_isaac_sim_version from .common import VecEnvObs, VecEnvStepReturn from .direct_rl_env_cfg import DirectRLEnvCfg diff --git a/source/isaaclab/isaaclab/envs/ui/base_env_window.py b/source/isaaclab/isaaclab/envs/ui/base_env_window.py index 52978453bf1..054a796a918 100644 --- a/source/isaaclab/isaaclab/envs/ui/base_env_window.py +++ b/source/isaaclab/isaaclab/envs/ui/base_env_window.py @@ -170,8 +170,8 @@ def on_render_mode_changed(value: str): "tooltip": "Select a rendering mode\n" + (RenderMode.__doc__ or ""), "on_clicked_fn": on_render_mode_changed, } - self.ui_window_elements["render_dropdown"] = ( - isaacsim.gui.components.ui_utils.dropdown_builder(**render_mode_cfg) + self.ui_window_elements["render_dropdown"] = isaacsim.gui.components.ui_utils.dropdown_builder( + **render_mode_cfg ) def _build_viewer_frame(self): diff --git a/source/isaaclab/test/controllers/test_operational_space.py b/source/isaaclab/test/controllers/test_operational_space.py index bd0a63a717c..e4de98da4ba 100644 --- a/source/isaaclab/test/controllers/test_operational_space.py +++ b/source/isaaclab/test/controllers/test_operational_space.py @@ -223,7 +223,7 @@ def sim(): ) # Cleanup - sim.stop() + sim.stop() sim.clear_instance() diff --git a/source/isaaclab/test/sim/test_mjcf_converter.py b/source/isaaclab/test/sim/test_mjcf_converter.py index 41b34db4a9b..d18f9250ba6 100644 --- a/source/isaaclab/test/sim/test_mjcf_converter.py +++ b/source/isaaclab/test/sim/test_mjcf_converter.py @@ -48,7 +48,7 @@ def test_setup_teardown(): yield sim, config # Teardown: Cleanup simulation - sim.stop() + sim.stop() sim.clear_instance() diff --git a/source/isaaclab/test/sim/test_spawn_meshes.py b/source/isaaclab/test/sim/test_spawn_meshes.py index 0ca2559843e..c76f5118bd6 100644 --- a/source/isaaclab/test/sim/test_spawn_meshes.py +++ b/source/isaaclab/test/sim/test_spawn_meshes.py @@ -34,7 +34,7 @@ def sim(): yield sim # Cleanup sim._disable_app_control_on_stop_handle = True # prevent timeout - sim.stop() + sim.stop() sim.clear_instance() diff --git a/source/isaaclab/test/sim/test_spawn_sensors.py b/source/isaaclab/test/sim/test_spawn_sensors.py index f66b2e740d5..3a582a8670a 100644 --- a/source/isaaclab/test/sim/test_spawn_sensors.py +++ b/source/isaaclab/test/sim/test_spawn_sensors.py @@ -32,7 +32,7 @@ def sim(): sim = SimulationContext(SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=dt))) sim_utils.update_stage() yield sim - sim.stop() + sim.stop() sim.clear_instance() diff --git a/source/isaaclab_contrib/isaaclab_contrib/sensors/tacsl_sensor/visuotactile_sensor.py b/source/isaaclab_contrib/isaaclab_contrib/sensors/tacsl_sensor/visuotactile_sensor.py index 8037ecb06a9..1af80e3af0d 100644 --- a/source/isaaclab_contrib/isaaclab_contrib/sensors/tacsl_sensor/visuotactile_sensor.py +++ b/source/isaaclab_contrib/isaaclab_contrib/sensors/tacsl_sensor/visuotactile_sensor.py @@ -18,11 +18,11 @@ import isaaclab.sim as sim_utils import isaaclab.utils.math as math_utils -from isaaclab.utils.math import quat_apply, quat_inv -from isaaclab.sim import SimulationContext from isaaclab.markers import VisualizationMarkers from isaaclab.sensors.camera import Camera, TiledCamera from isaaclab.sensors.sensor_base import SensorBase +from isaaclab.sim import SimulationContext +from isaaclab.utils.math import quat_apply, quat_inv from .visuotactile_render import GelsightRender from .visuotactile_sensor_data import VisuoTactileSensorData diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/automate/assembly_env.py b/source/isaaclab_tasks/isaaclab_tasks/direct/automate/assembly_env.py index 29f47aed0f4..d1dbddc0b46 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/automate/assembly_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/automate/assembly_env.py @@ -13,7 +13,12 @@ import carb import isaaclab.sim as sim_utils +from isaaclab.assets import Articulation, RigidObject +from isaaclab.envs import DirectRLEnv +from isaaclab.sim.spawners.from_files import GroundPlaneCfg, spawn_ground_plane +from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR, retrieve_file_path from isaaclab.utils.math import ( + axis_angle_from_quat, combine_frame_transforms, euler_xyz_from_quat, quat_conjugate, @@ -21,11 +26,6 @@ quat_from_euler_xyz, quat_mul, ) -from isaaclab.assets import Articulation, RigidObject -from isaaclab.envs import DirectRLEnv -from isaaclab.sim.spawners.from_files import GroundPlaneCfg, spawn_ground_plane -from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR, retrieve_file_path -from isaaclab.utils.math import axis_angle_from_quat from . import automate_algo_utils as automate_algo from . import automate_log_utils as automate_log @@ -320,9 +320,7 @@ def _compute_intermediate_values(self, dt): self.prev_fingertip_pos = self.fingertip_midpoint_pos.clone() # Add state differences if velocity isn't being added. - rot_diff_quat = quat_mul( - self.fingertip_midpoint_quat, quat_conjugate(self.prev_fingertip_quat) - ) + rot_diff_quat = quat_mul(self.fingertip_midpoint_quat, quat_conjugate(self.prev_fingertip_quat)) rot_diff_quat *= torch.sign(rot_diff_quat[:, 3]).unsqueeze(-1) # W component is at index 3 in XYZW format rot_diff_aa = axis_angle_from_quat(rot_diff_quat) self.ee_angvel_fd = rot_diff_aa / dt @@ -773,9 +771,7 @@ def randomize_fixed_initial_state(self, env_ids): rand_sample = torch.rand((len(env_ids), 3), dtype=torch.float32, device=self.device) fixed_orn_euler = fixed_orn_init_yaw + fixed_orn_yaw_range * rand_sample fixed_orn_euler[:, 0:2] = 0.0 # Only change yaw. - fixed_orn_quat = quat_from_euler_xyz( - fixed_orn_euler[:, 0], fixed_orn_euler[:, 1], fixed_orn_euler[:, 2] - ) + fixed_orn_quat = quat_from_euler_xyz(fixed_orn_euler[:, 0], fixed_orn_euler[:, 1], fixed_orn_euler[:, 2]) fixed_state[:, 3:7] = fixed_orn_quat # (1.c.) Velocity fixed_state[:, 7:] = 0.0 # vel diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/automate/disassembly_env.py b/source/isaaclab_tasks/isaaclab_tasks/direct/automate/disassembly_env.py index 59d6ee8b648..5410599f0a4 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/automate/disassembly_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/automate/disassembly_env.py @@ -241,9 +241,7 @@ def _compute_intermediate_values(self, dt): self.prev_fingertip_pos = self.fingertip_midpoint_pos.clone() # Add state differences if velocity isn't being added. - rot_diff_quat = quat_mul( - self.fingertip_midpoint_quat, quat_conjugate(self.prev_fingertip_quat) - ) + rot_diff_quat = quat_mul(self.fingertip_midpoint_quat, quat_conjugate(self.prev_fingertip_quat)) rot_diff_quat *= torch.sign(rot_diff_quat[:, 3]).unsqueeze(-1) # W component is at index 3 in XYZW format rot_diff_aa = axis_angle_from_quat(rot_diff_quat) self.ee_angvel_fd = rot_diff_aa / dt @@ -640,9 +638,7 @@ def randomize_fixed_initial_state(self, env_ids): rand_sample = torch.rand((len(env_ids), 3), dtype=torch.float32, device=self.device) fixed_orn_euler = fixed_orn_init_yaw + fixed_orn_yaw_range * rand_sample fixed_orn_euler[:, 0:2] = 0.0 # Only change yaw. - fixed_orn_quat = quat_from_euler_xyz( - fixed_orn_euler[:, 0], fixed_orn_euler[:, 1], fixed_orn_euler[:, 2] - ) + fixed_orn_quat = quat_from_euler_xyz(fixed_orn_euler[:, 0], fixed_orn_euler[:, 1], fixed_orn_euler[:, 2]) fixed_state[:, 3:7] = fixed_orn_quat # (1.c.) Velocity fixed_state[:, 7:] = 0.0 # vel diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/automate/factory_control.py b/source/isaaclab_tasks/isaaclab_tasks/direct/automate/factory_control.py index 885a1629f3e..2d7d98e0fb0 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/automate/factory_control.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/automate/factory_control.py @@ -114,12 +114,12 @@ def get_pose_error( quat_dot.expand(-1, 4) >= 0, ctrl_target_fingertip_midpoint_quat, -ctrl_target_fingertip_midpoint_quat ) - fingertip_midpoint_quat_norm = quat_mul( - fingertip_midpoint_quat, quat_conjugate(fingertip_midpoint_quat) - )[:, 3] # W component is at index 3 in XYZW format - fingertip_midpoint_quat_inv = quat_conjugate( - fingertip_midpoint_quat - ) / fingertip_midpoint_quat_norm.unsqueeze(-1) + fingertip_midpoint_quat_norm = quat_mul(fingertip_midpoint_quat, quat_conjugate(fingertip_midpoint_quat))[ + :, 3 + ] # W component is at index 3 in XYZW format + fingertip_midpoint_quat_inv = quat_conjugate(fingertip_midpoint_quat) / fingertip_midpoint_quat_norm.unsqueeze( + -1 + ) quat_error = quat_mul(ctrl_target_fingertip_midpoint_quat, fingertip_midpoint_quat_inv) # Convert to axis-angle error diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/forge/forge_env.py b/source/isaaclab_tasks/isaaclab_tasks/direct/forge/forge_env.py index ac296bc597e..3aaa950fa0f 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/forge/forge_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/forge/forge_env.py @@ -87,9 +87,7 @@ def _compute_intermediate_values(self, dt): self.prev_fingertip_pos = self.noisy_fingertip_pos.clone() # Add state differences if velocity isn't being added. - rot_diff_quat = quat_mul( - self.noisy_fingertip_quat, quat_conjugate(self.prev_fingertip_quat) - ) + rot_diff_quat = quat_mul(self.noisy_fingertip_quat, quat_conjugate(self.prev_fingertip_quat)) rot_diff_quat *= torch.sign(rot_diff_quat[:, 3]).unsqueeze(-1) # W component is at index 3 in XYZW format rot_diff_aa = axis_angle_from_quat(rot_diff_quat) self.ee_angvel_fd = rot_diff_aa / dt @@ -170,9 +168,7 @@ def _apply_action(self): # Assumes joint limit is in (+x, -y)-quadrant of world frame. rot_actions[:, 2] = np.deg2rad(-180.0) + np.deg2rad(270.0) * (rot_actions[:, 2] + 1.0) / 2.0 # Joint limit. # (1.c) Get desired orientation target. - bolt_frame_quat = quat_from_euler_xyz( - roll=rot_actions[:, 0], pitch=rot_actions[:, 1], yaw=rot_actions[:, 2] - ) + bolt_frame_quat = quat_from_euler_xyz(roll=rot_actions[:, 0], pitch=rot_actions[:, 1], yaw=rot_actions[:, 2]) rot_180_euler = torch.tensor([np.pi, 0.0, 0.0], device=self.device).repeat(self.num_envs, 1) quat_bolt_to_ee = quat_from_euler_xyz( diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/forge/forge_utils.py b/source/isaaclab_tasks/isaaclab_tasks/direct/forge/forge_utils.py index b7bc5315170..0e575b14c88 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/forge/forge_utils.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/forge/forge_utils.py @@ -44,7 +44,5 @@ def change_FT_frame(source_F, source_T, source_frame, target_frame): ) target_F = quat_apply(target_T_source_quat, source_F) - target_T = quat_apply( - target_T_source_quat, (source_T + torch.cross(target_T_source_pos, source_F, dim=-1)) - ) + target_T = quat_apply(target_T_source_quat, (source_T + torch.cross(target_T_source_pos, source_F, dim=-1))) return target_F, target_T From cc2fc63399690be352774416638187f9a249bcfe Mon Sep 17 00:00:00 2001 From: Octi Zhang Date: Sun, 8 Feb 2026 12:40:39 -0800 Subject: [PATCH 24/46] rename drop manager for cfg for simplicity --- .../benchmarks/benchmark_view_comparison.py | 4 +- scripts/demos/bin_packing.py | 4 +- scripts/demos/bipeds.py | 4 +- scripts/demos/deformables.py | 4 +- scripts/demos/hands.py | 4 +- scripts/demos/markers.py | 4 +- scripts/demos/multi_asset.py | 4 +- scripts/demos/procedural_terrain.py | 4 +- scripts/demos/quadcopter.py | 6 +- scripts/demos/quadrupeds.py | 4 +- scripts/demos/sensors/cameras.py | 4 +- scripts/demos/sensors/contact_sensor.py | 4 +- .../demos/sensors/frame_transformer_sensor.py | 4 +- scripts/demos/sensors/imu_sensor.py | 4 +- scripts/demos/sensors/multi_mesh_raycaster.py | 4 +- .../sensors/multi_mesh_raycaster_camera.py | 4 +- scripts/demos/sensors/raycaster_sensor.py | 4 +- scripts/tools/check_instanceable.py | 4 +- scripts/tutorials/00_sim/create_empty.py | 4 +- scripts/tutorials/00_sim/launch_app.py | 4 +- scripts/tutorials/00_sim/log_time.py | 4 +- scripts/tutorials/00_sim/spawn_prims.py | 4 +- .../04_sensors/add_sensors_on_robot.py | 4 +- .../04_sensors/run_frame_transformer.py | 4 +- .../tutorials/05_controllers/run_diff_ik.py | 4 +- scripts/tutorials/05_controllers/run_osc.py | 4 +- .../isaaclab/isaaclab/envs/direct_rl_env.py | 6 +- .../isaaclab/envs/manager_based_env.py | 4 +- source/isaaclab/isaaclab/physics/__init__.py | 4 +- .../isaaclab/physics/physics_manager.py | 2 +- .../isaaclab/physics/physics_manager_cfg.py | 9 +- source/isaaclab/isaaclab/sim/__init__.py | 10 +- .../isaaclab/isaaclab/sim/simulation_cfg.py | 152 +++++++++--------- .../isaaclab/sim/simulation_context.py | 14 +- .../test/app/test_non_headless_launch.py | 4 +- .../test/assets/check_external_force.py | 4 +- .../test/assets/check_fixed_base_assets.py | 4 +- .../test/controllers/test_differential_ik.py | 4 +- .../controllers/test_operational_space.py | 4 +- .../isaaclab/test/devices/check_keyboard.py | 4 +- .../test/envs/test_env_rendering_logic.py | 14 +- .../test/managers/test_observation_manager.py | 4 +- .../test/markers/check_markers_visibility.py | 4 +- .../markers/test_visualization_markers.py | 4 +- .../test/scene/check_interactive_scene.py | 4 +- source/isaaclab/test/sensors/test_camera.py | 4 +- .../test_multi_mesh_ray_caster_camera.py | 4 +- .../test/sensors/test_multi_tiled_camera.py | 4 +- .../test/sensors/test_ray_caster_camera.py | 4 +- .../isaaclab/test/sensors/test_sensor_base.py | 4 +- .../test/sensors/test_tiled_camera.py | 4 +- source/isaaclab/test/sim/check_meshes.py | 4 +- .../test_build_simulation_context_headless.py | 14 +- ...st_build_simulation_context_nonheadless.py | 14 +- .../isaaclab/test/sim/test_mesh_converter.py | 4 +- .../isaaclab/test/sim/test_mjcf_converter.py | 4 +- source/isaaclab/test/sim/test_schemas.py | 4 +- .../test/sim/test_simulation_context.py | 64 ++++---- .../test/sim/test_spawn_from_files.py | 4 +- source/isaaclab/test/sim/test_spawn_lights.py | 4 +- .../isaaclab/test/sim/test_spawn_materials.py | 4 +- source/isaaclab/test/sim/test_spawn_meshes.py | 4 +- .../isaaclab/test/sim/test_spawn_sensors.py | 4 +- source/isaaclab/test/sim/test_spawn_shapes.py | 4 +- .../isaaclab/test/sim/test_spawn_wrappers.py | 4 +- .../isaaclab/test/sim/test_urdf_converter.py | 4 +- .../test/sim/test_views_xform_prim.py | 6 +- .../test/terrains/check_terrain_importer.py | 2 +- .../test/terrains/test_terrain_importer.py | 2 +- .../check_scene_xr_visualization.py | 4 +- .../test/sensors/test_visuotactile_sensor.py | 4 +- .../isaaclab_physx/physics/__init__.py | 4 +- .../isaaclab_physx/physics/physx_manager.py | 4 +- .../physics/physx_manager_cfg.py | 4 +- .../test/sensors/check_contact_sensor.py | 4 +- .../test/sensors/test_contact_sensor.py | 8 +- .../test/sensors/test_frame_transformer.py | 4 +- .../isaaclab_physx/test/sensors/test_imu.py | 4 +- .../allegro_hand/allegro_hand_env_cfg.py | 4 +- .../isaaclab_tasks/direct/ant/ant_env.py | 4 +- .../direct/anymal_c/anymal_c_env_cfg.py | 4 +- .../direct/automate/assembly_env_cfg.py | 4 +- .../direct/automate/disassembly_env_cfg.py | 5 +- .../cart_double_pendulum_env.py | 4 +- .../direct/cartpole/cartpole_camera_env.py | 4 +- .../direct/cartpole/cartpole_env.py | 4 +- .../direct/factory/factory_env_cfg.py | 4 +- .../franka_cabinet/franka_cabinet_env.py | 4 +- .../direct/humanoid/humanoid_env.py | 4 +- .../humanoid_amp/humanoid_amp_env_cfg.py | 4 +- .../direct/quadcopter/quadcopter_env.py | 4 +- .../direct/shadow_hand/shadow_hand_env_cfg.py | 7 +- .../shadow_hand_over_env_cfg.py | 5 +- .../manager_based/classic/ant/ant_env_cfg.py | 4 +- .../classic/cartpole/cartpole_env_cfg.py | 2 +- .../classic/humanoid/humanoid_env_cfg.py | 4 +- .../config/arl_robot_1/no_obstacle_env_cfg.py | 2 +- .../track_position_state_based_env_cfg.py | 6 +- .../fixed_base_upper_body_ik_g1_env_cfg.py | 2 +- .../pick_place/locomanipulation_g1_env_cfg.py | 2 +- .../velocity/config/digit/rough_env_cfg.py | 6 +- .../velocity/config/spot/flat_env_cfg.py | 12 +- .../locomotion/velocity/velocity_env_cfg.py | 10 +- .../manipulation/cabinet/cabinet_env_cfg.py | 6 +- .../config/openarm/cabinet_openarm_env_cfg.py | 6 +- .../gear_assembly/gear_assembly_env_cfg.py | 6 +- .../deploy/reach/reach_env_cfg.py | 2 +- .../manipulation/dexsuite/dexsuite_env_cfg.py | 6 +- .../manipulation/inhand/inhand_env_cfg.py | 6 +- .../config/openarm/lift_openarm_env_cfg.py | 10 +- .../manipulation/lift/lift_env_cfg.py | 10 +- .../exhaustpipe_gr1t2_base_env_cfg.py | 2 +- .../pick_place/nutpour_gr1t2_base_env_cfg.py | 2 +- .../pick_place/pickplace_gr1t2_env_cfg.py | 2 +- .../pickplace_gr1t2_waist_enabled_env_cfg.py | 2 +- ...ckplace_unitree_g1_inspire_hand_env_cfg.py | 2 +- .../agibot/place_toy2box_rmp_rel_env_cfg.py | 10 +- .../place_upright_mug_rmp_rel_env_cfg.py | 2 +- .../bimanual/reach_openarm_bi_env_cfg.py | 2 +- .../unimanual/reach_openarm_uni_env_cfg.py | 2 +- .../manipulation/reach/reach_env_cfg.py | 2 +- .../config/galbot/stack_rmp_rel_env_cfg.py | 6 +- .../ur10_gripper/stack_joint_pos_env_cfg.py | 2 +- .../manipulation/stack/stack_env_cfg.py | 10 +- .../stack/stack_instance_randomize_env_cfg.py | 10 +- .../config/anymal_c/navigation_env_cfg.py | 6 +- 126 files changed, 397 insertions(+), 407 deletions(-) diff --git a/scripts/benchmarks/benchmark_view_comparison.py b/scripts/benchmarks/benchmark_view_comparison.py index 1b743135e7c..48465694360 100644 --- a/scripts/benchmarks/benchmark_view_comparison.py +++ b/scripts/benchmarks/benchmark_view_comparison.py @@ -69,7 +69,7 @@ import time import torch -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.sim.views import XformPrimView @@ -98,7 +98,7 @@ def benchmark_view(view_type: str, num_iterations: int) -> tuple[dict[str, float # Create simulation context start_time = time.perf_counter() sim_cfg = sim_utils.SimulationCfg( - device=args_cli.device, physics_manager_cfg=PhysxManagerCfg(dt=0.01, use_fabric=(view_type == "xform_fabric")) + device=args_cli.device, physics=PhysxCfg(dt=0.01, use_fabric=(view_type == "xform_fabric")) ) sim = sim_utils.SimulationContext(sim_cfg) stage = sim_utils.get_current_stage() diff --git a/scripts/demos/bin_packing.py b/scripts/demos/bin_packing.py index 732d08b73c4..48c6271a617 100644 --- a/scripts/demos/bin_packing.py +++ b/scripts/demos/bin_packing.py @@ -44,7 +44,7 @@ import math import torch -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils import isaaclab.utils.math as math_utils @@ -328,7 +328,7 @@ def main() -> None: None: The function drives the simulation for its side-effects. """ # Load kit helper - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics_manager_cfg=PhysxManagerCfg(dt=0.005)) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics=PhysxCfg(dt=0.005)) sim = SimulationContext(sim_cfg) # Set main camera sim.set_camera_view((2.5, 0.0, 4.0), (0.0, 0.0, 2.0)) diff --git a/scripts/demos/bipeds.py b/scripts/demos/bipeds.py index ac34dd28f5e..85b363fd74a 100644 --- a/scripts/demos/bipeds.py +++ b/scripts/demos/bipeds.py @@ -33,7 +33,7 @@ """Rest everything follows.""" import torch -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import Articulation @@ -115,7 +115,7 @@ def run_simulator(sim: sim_utils.SimulationContext, robots: list[Articulation], def main(): """Main function.""" # Load kit helper - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics_manager_cfg=PhysxManagerCfg(dt=0.005)) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics=PhysxCfg(dt=0.005)) sim = SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[3.0, 0.0, 2.25], target=[0.0, 0.0, 1.0]) diff --git a/scripts/demos/deformables.py b/scripts/demos/deformables.py index 41c92dc8465..630a36f73c2 100644 --- a/scripts/demos/deformables.py +++ b/scripts/demos/deformables.py @@ -36,7 +36,7 @@ import numpy as np import torch import tqdm -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import DeformableObject, DeformableObjectCfg @@ -179,7 +179,7 @@ def run_simulator(sim: sim_utils.SimulationContext, entities: dict[str, Deformab def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics_manager_cfg=PhysxManagerCfg(dt=0.01)) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics=PhysxCfg(dt=0.01)) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view([4.0, 4.0, 3.0], [0.5, 0.5, 0.0]) diff --git a/scripts/demos/hands.py b/scripts/demos/hands.py index 1012e4b5680..462b5c2bff4 100644 --- a/scripts/demos/hands.py +++ b/scripts/demos/hands.py @@ -34,7 +34,7 @@ import numpy as np import torch -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import Articulation @@ -144,7 +144,7 @@ def run_simulator(sim: sim_utils.SimulationContext, entities: dict[str, Articula def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics_manager_cfg=PhysxManagerCfg(dt=0.01)) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics=PhysxCfg(dt=0.01)) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[0.0, -0.5, 1.5], target=[0.0, -0.2, 0.5]) diff --git a/scripts/demos/markers.py b/scripts/demos/markers.py index ca99bde625e..834bc9a7d26 100644 --- a/scripts/demos/markers.py +++ b/scripts/demos/markers.py @@ -32,7 +32,7 @@ """Rest everything follows.""" import torch -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.markers import VisualizationMarkers, VisualizationMarkersCfg @@ -95,7 +95,7 @@ def define_markers() -> VisualizationMarkers: def main(): """Main function.""" # Load kit helper - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics_manager_cfg=PhysxManagerCfg(dt=0.01)) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics=PhysxCfg(dt=0.01)) sim = SimulationContext(sim_cfg) # Set main camera sim.set_camera_view([0.0, 18.0, 12.0], [0.0, 3.0, 0.0]) diff --git a/scripts/demos/multi_asset.py b/scripts/demos/multi_asset.py index 6834ef015c0..825e1e68ee4 100644 --- a/scripts/demos/multi_asset.py +++ b/scripts/demos/multi_asset.py @@ -37,7 +37,7 @@ import random -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg from pxr import Gf, Sdf @@ -277,7 +277,7 @@ def run_simulator(sim: SimulationContext, scene: InteractiveScene): def main(): """Main function.""" # Load kit helper - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics_manager_cfg=PhysxManagerCfg(dt=0.005)) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics=PhysxCfg(dt=0.005)) sim = SimulationContext(sim_cfg) # Set main camera sim.set_camera_view([2.5, 0.0, 4.0], [0.0, 0.0, 2.0]) diff --git a/scripts/demos/procedural_terrain.py b/scripts/demos/procedural_terrain.py index 4f7fc456f56..c5b48ff6ae2 100644 --- a/scripts/demos/procedural_terrain.py +++ b/scripts/demos/procedural_terrain.py @@ -68,7 +68,7 @@ import random import torch -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import AssetBase @@ -155,7 +155,7 @@ def run_simulator(sim: sim_utils.SimulationContext, entities: dict[str, AssetBas def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics_manager_cfg=PhysxManagerCfg(dt=0.01)) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics=PhysxCfg(dt=0.01)) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[5.0, 5.0, 5.0], target=[0.0, 0.0, 0.0]) diff --git a/scripts/demos/quadcopter.py b/scripts/demos/quadcopter.py index 05aec2aaba1..8f8f2d0677f 100644 --- a/scripts/demos/quadcopter.py +++ b/scripts/demos/quadcopter.py @@ -33,7 +33,7 @@ """Rest everything follows.""" import torch -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import Articulation @@ -48,7 +48,7 @@ def main(): """Main function.""" # Load kit helper - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics_manager_cfg=PhysxManagerCfg(dt=0.005)) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics=PhysxCfg(dt=0.005)) sim = SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[0.5, 0.5, 1.0], target=[0.0, 0.0, 0.5]) @@ -74,7 +74,7 @@ def main(): # Fetch relevant parameters to make the quadcopter hover in place prop_body_ids = robot.find_bodies("m.*_prop")[0] robot_mass = robot.root_view.get_masses().sum() - gravity = torch.tensor(sim.cfg.physics_manager_cfg.gravity, device=sim.device).norm() + gravity = torch.tensor(sim.cfg.physics.gravity, device=sim.device).norm() # Now we are ready! print("[INFO]: Setup complete...") diff --git a/scripts/demos/quadrupeds.py b/scripts/demos/quadrupeds.py index d970b2413ba..14d78a509cc 100644 --- a/scripts/demos/quadrupeds.py +++ b/scripts/demos/quadrupeds.py @@ -34,7 +34,7 @@ import numpy as np import torch -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import Articulation @@ -171,7 +171,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim = sim_utils.SimulationContext(sim_utils.SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01))) + sim = sim_utils.SimulationContext(sim_utils.SimulationCfg(physics=PhysxCfg(dt=0.01))) # Set main camera sim.set_camera_view(eye=[2.5, 2.5, 2.5], target=[0.0, 0.0, 0.0]) # design scene diff --git a/scripts/demos/sensors/cameras.py b/scripts/demos/sensors/cameras.py index f107c73d49e..e5b57ec4f18 100644 --- a/scripts/demos/sensors/cameras.py +++ b/scripts/demos/sensors/cameras.py @@ -42,7 +42,7 @@ import matplotlib.pyplot as plt import numpy as np import torch -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import ArticulationCfg, AssetBaseCfg @@ -282,7 +282,7 @@ def main(): """Main function.""" # Initialize the simulation context sim_cfg = sim_utils.SimulationCfg( - device=args_cli.device, physics_manager_cfg=PhysxManagerCfg(dt=0.005, use_fabric=not args_cli.disable_fabric) + device=args_cli.device, physics=PhysxCfg(dt=0.005, use_fabric=not args_cli.disable_fabric) ) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera diff --git a/scripts/demos/sensors/contact_sensor.py b/scripts/demos/sensors/contact_sensor.py index 5a09d5f5fb6..05dfce51a78 100644 --- a/scripts/demos/sensors/contact_sensor.py +++ b/scripts/demos/sensors/contact_sensor.py @@ -24,7 +24,7 @@ """Rest everything follows.""" import torch -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import AssetBaseCfg, RigidObjectCfg @@ -155,7 +155,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics_manager_cfg=PhysxManagerCfg(dt=0.005)) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics=PhysxCfg(dt=0.005)) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) diff --git a/scripts/demos/sensors/frame_transformer_sensor.py b/scripts/demos/sensors/frame_transformer_sensor.py index e97bf446dae..5a0848bea72 100644 --- a/scripts/demos/sensors/frame_transformer_sensor.py +++ b/scripts/demos/sensors/frame_transformer_sensor.py @@ -22,7 +22,7 @@ """Rest everything follows.""" import torch -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import AssetBaseCfg, RigidObjectCfg @@ -149,7 +149,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics_manager_cfg=PhysxManagerCfg(dt=0.005)) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics=PhysxCfg(dt=0.005)) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) diff --git a/scripts/demos/sensors/imu_sensor.py b/scripts/demos/sensors/imu_sensor.py index e4e47d30799..e86e02630e3 100644 --- a/scripts/demos/sensors/imu_sensor.py +++ b/scripts/demos/sensors/imu_sensor.py @@ -24,7 +24,7 @@ """Rest everything follows.""" import torch -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import AssetBaseCfg @@ -122,7 +122,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics_manager_cfg=PhysxManagerCfg(dt=0.005)) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics=PhysxCfg(dt=0.005)) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) diff --git a/scripts/demos/sensors/multi_mesh_raycaster.py b/scripts/demos/sensors/multi_mesh_raycaster.py index c8875f1dba8..fa6fbb68496 100644 --- a/scripts/demos/sensors/multi_mesh_raycaster.py +++ b/scripts/demos/sensors/multi_mesh_raycaster.py @@ -47,7 +47,7 @@ import random import torch -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import omni.usd from pxr import Gf, Sdf @@ -278,7 +278,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics_manager_cfg=PhysxManagerCfg(dt=0.005)) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics=PhysxCfg(dt=0.005)) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) diff --git a/scripts/demos/sensors/multi_mesh_raycaster_camera.py b/scripts/demos/sensors/multi_mesh_raycaster_camera.py index 0ef22ef6cc3..43e601583e5 100644 --- a/scripts/demos/sensors/multi_mesh_raycaster_camera.py +++ b/scripts/demos/sensors/multi_mesh_raycaster_camera.py @@ -47,7 +47,7 @@ import random import torch -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import omni.usd from pxr import Gf, Sdf @@ -304,7 +304,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics_manager_cfg=PhysxManagerCfg(dt=0.005)) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics=PhysxCfg(dt=0.005)) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) diff --git a/scripts/demos/sensors/raycaster_sensor.py b/scripts/demos/sensors/raycaster_sensor.py index 8e4c1343c4c..962e9d56470 100644 --- a/scripts/demos/sensors/raycaster_sensor.py +++ b/scripts/demos/sensors/raycaster_sensor.py @@ -23,7 +23,7 @@ import numpy as np import torch -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import AssetBaseCfg @@ -140,7 +140,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics_manager_cfg=PhysxManagerCfg(dt=0.005)) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics=PhysxCfg(dt=0.005)) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) diff --git a/scripts/tools/check_instanceable.py b/scripts/tools/check_instanceable.py index a61e33b7984..73be99c66a7 100644 --- a/scripts/tools/check_instanceable.py +++ b/scripts/tools/check_instanceable.py @@ -64,7 +64,7 @@ """Rest everything follows.""" -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg from isaacsim.core.cloner import GridCloner @@ -80,7 +80,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(SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01))) + sim = SimulationContext(SimulationCfg(physics=PhysxCfg(dt=0.01))) # get stage handle stage = sim_utils.get_current_stage() diff --git a/scripts/tutorials/00_sim/create_empty.py b/scripts/tutorials/00_sim/create_empty.py index 67e634e96d7..ff96d84c1f1 100644 --- a/scripts/tutorials/00_sim/create_empty.py +++ b/scripts/tutorials/00_sim/create_empty.py @@ -31,7 +31,7 @@ """Rest everything follows.""" -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg from isaaclab.sim import SimulationCfg, SimulationContext @@ -40,7 +40,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim_cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01)) + sim_cfg = SimulationCfg(physics=PhysxCfg(dt=0.01)) sim = SimulationContext(sim_cfg) # Set main camera sim.set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0]) diff --git a/scripts/tutorials/00_sim/launch_app.py b/scripts/tutorials/00_sim/launch_app.py index ee70497e733..5b4e4b41220 100644 --- a/scripts/tutorials/00_sim/launch_app.py +++ b/scripts/tutorials/00_sim/launch_app.py @@ -41,7 +41,7 @@ """Rest everything follows.""" -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils @@ -72,7 +72,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics_manager_cfg=PhysxManagerCfg(dt=0.01)) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics=PhysxCfg(dt=0.01)) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view([2.0, 0.0, 2.5], [-0.5, 0.0, 0.5]) diff --git a/scripts/tutorials/00_sim/log_time.py b/scripts/tutorials/00_sim/log_time.py index d0d0431d051..5934c9b387d 100644 --- a/scripts/tutorials/00_sim/log_time.py +++ b/scripts/tutorials/00_sim/log_time.py @@ -34,7 +34,7 @@ """Rest everything follows.""" -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg from isaaclab.sim import SimulationCfg, SimulationContext @@ -55,7 +55,7 @@ def main(): print(f"[INFO] Logging experiment to directory: {log_dir_path}") # Initialize the simulation context - sim_cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01)) + sim_cfg = SimulationCfg(physics=PhysxCfg(dt=0.01)) sim = SimulationContext(sim_cfg) # Set main camera sim.set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0]) diff --git a/scripts/tutorials/00_sim/spawn_prims.py b/scripts/tutorials/00_sim/spawn_prims.py index 08cf100b36a..3b15b2d6e52 100644 --- a/scripts/tutorials/00_sim/spawn_prims.py +++ b/scripts/tutorials/00_sim/spawn_prims.py @@ -31,7 +31,7 @@ """Rest everything follows.""" -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR @@ -92,7 +92,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics_manager_cfg=PhysxManagerCfg(dt=0.01)) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics=PhysxCfg(dt=0.01)) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view([2.0, 0.0, 2.5], [-0.5, 0.0, 0.5]) diff --git a/scripts/tutorials/04_sensors/add_sensors_on_robot.py b/scripts/tutorials/04_sensors/add_sensors_on_robot.py index 8188016eb96..f64c38751f8 100644 --- a/scripts/tutorials/04_sensors/add_sensors_on_robot.py +++ b/scripts/tutorials/04_sensors/add_sensors_on_robot.py @@ -40,7 +40,7 @@ """Rest everything follows.""" import torch -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import ArticulationCfg, AssetBaseCfg @@ -158,7 +158,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics_manager_cfg=PhysxManagerCfg(dt=0.005)) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics=PhysxCfg(dt=0.005)) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) diff --git a/scripts/tutorials/04_sensors/run_frame_transformer.py b/scripts/tutorials/04_sensors/run_frame_transformer.py index 661de27bdc7..748b26ed699 100644 --- a/scripts/tutorials/04_sensors/run_frame_transformer.py +++ b/scripts/tutorials/04_sensors/run_frame_transformer.py @@ -35,7 +35,7 @@ import math import torch -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import isaacsim.util.debug_draw._debug_draw as omni_debug_draw @@ -166,7 +166,7 @@ def run_simulator(sim: sim_utils.SimulationContext, scene_entities: dict): def main(): """Main function.""" # Load kit helper - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics_manager_cfg=PhysxManagerCfg(dt=0.005)) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics=PhysxCfg(dt=0.005)) sim = SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[2.5, 2.5, 2.5], target=[0.0, 0.0, 0.0]) diff --git a/scripts/tutorials/05_controllers/run_diff_ik.py b/scripts/tutorials/05_controllers/run_diff_ik.py index 2a66e334526..1a0e83c601f 100644 --- a/scripts/tutorials/05_controllers/run_diff_ik.py +++ b/scripts/tutorials/05_controllers/run_diff_ik.py @@ -38,7 +38,7 @@ """Rest everything follows.""" import torch -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import AssetBaseCfg @@ -191,7 +191,7 @@ def run_simulator(sim: sim_utils.SimulationContext, scene: InteractiveScene): def main(): """Main function.""" # Load kit helper - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics_manager_cfg=PhysxManagerCfg(dt=0.01)) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics=PhysxCfg(dt=0.01)) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0]) diff --git a/scripts/tutorials/05_controllers/run_osc.py b/scripts/tutorials/05_controllers/run_osc.py index 7116f2b049c..283e17d84fa 100644 --- a/scripts/tutorials/05_controllers/run_osc.py +++ b/scripts/tutorials/05_controllers/run_osc.py @@ -37,7 +37,7 @@ """Rest everything follows.""" import torch -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import Articulation, AssetBaseCfg @@ -463,7 +463,7 @@ def convert_to_task_frame(osc: OperationalSpaceController, command: torch.tensor def main(): """Main function.""" # Load kit helper - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics_manager_cfg=PhysxManagerCfg(dt=0.01)) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics=PhysxCfg(dt=0.01)) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0]) diff --git a/source/isaaclab/isaaclab/envs/direct_rl_env.py b/source/isaaclab/isaaclab/envs/direct_rl_env.py index f9c141b4fe4..5b4567acda0 100644 --- a/source/isaaclab/isaaclab/envs/direct_rl_env.py +++ b/source/isaaclab/isaaclab/envs/direct_rl_env.py @@ -258,7 +258,7 @@ def physics_dt(self) -> float: This is the lowest time-decimation at which the simulation is happening. """ - return self.cfg.sim.physics_manager_cfg.dt + return self.cfg.sim.physics.dt @property def step_dt(self) -> float: @@ -266,7 +266,7 @@ def step_dt(self) -> float: This is the time-step at which the environment steps forward. """ - return self.cfg.sim.physics_manager_cfg.dt * self.cfg.decimation + return self.cfg.sim.physics.dt * self.cfg.decimation @property def device(self): @@ -281,7 +281,7 @@ def max_episode_length_s(self) -> float: @property def max_episode_length(self): """The maximum episode length in steps adjusted from s.""" - return math.ceil(self.max_episode_length_s / (self.cfg.sim.physics_manager_cfg.dt * self.cfg.decimation)) + return math.ceil(self.max_episode_length_s / (self.cfg.sim.physics.dt * self.cfg.decimation)) """ Operations. diff --git a/source/isaaclab/isaaclab/envs/manager_based_env.py b/source/isaaclab/isaaclab/envs/manager_based_env.py index 80af872f364..45a3d19591e 100644 --- a/source/isaaclab/isaaclab/envs/manager_based_env.py +++ b/source/isaaclab/isaaclab/envs/manager_based_env.py @@ -226,7 +226,7 @@ def physics_dt(self) -> float: This is the lowest time-decimation at which the simulation is happening. """ - return self.cfg.sim.physics_manager_cfg.dt + return self.cfg.sim.physics.dt @property def step_dt(self) -> float: @@ -234,7 +234,7 @@ def step_dt(self) -> float: This is the time-step at which the environment steps forward. """ - return self.cfg.sim.physics_manager_cfg.dt * self.cfg.decimation + return self.cfg.sim.physics.dt * self.cfg.decimation @property def device(self): diff --git a/source/isaaclab/isaaclab/physics/__init__.py b/source/isaaclab/isaaclab/physics/__init__.py index d61c06d65a3..6c885cb9847 100644 --- a/source/isaaclab/isaaclab/physics/__init__.py +++ b/source/isaaclab/isaaclab/physics/__init__.py @@ -6,11 +6,11 @@ """Implementation backends for simulation interfaces.""" from .physics_manager import PhysicsManager, PhysicsEvent, CallbackHandle -from .physics_manager_cfg import PhysicsManagerCfg +from .physics_manager_cfg import PhysicsCfg __all__ = [ "PhysicsManager", "PhysicsEvent", "CallbackHandle", - "PhysicsManagerCfg", + "PhysicsCfg", ] diff --git a/source/isaaclab/isaaclab/physics/physics_manager.py b/source/isaaclab/isaaclab/physics/physics_manager.py index e2820c3ed0b..3d176d182f0 100644 --- a/source/isaaclab/isaaclab/physics/physics_manager.py +++ b/source/isaaclab/isaaclab/physics/physics_manager.py @@ -250,7 +250,7 @@ def initialize(cls, sim_context: SimulationContext) -> None: # Set on PhysicsManager explicitly so PhysicsManager.get_*() works # regardless of which subclass is active (Python class vars are per-class) PhysicsManager._sim = sim_context - PhysicsManager._cfg = sim_context.cfg.physics_manager_cfg + PhysicsManager._cfg = sim_context.cfg.physics PhysicsManager._device = sim_context.cfg.device PhysicsManager._sim_time = 0.0 diff --git a/source/isaaclab/isaaclab/physics/physics_manager_cfg.py b/source/isaaclab/isaaclab/physics/physics_manager_cfg.py index e400d984ced..a39a189ad52 100644 --- a/source/isaaclab/isaaclab/physics/physics_manager_cfg.py +++ b/source/isaaclab/isaaclab/physics/physics_manager_cfg.py @@ -18,7 +18,7 @@ @configclass -class PhysicsManagerCfg: +class PhysicsCfg: """Abstract base configuration for physics managers. This base class contains common simulation parameters shared across @@ -49,3 +49,10 @@ class PhysicsManagerCfg: The material is created at the path: ``{physics_prim_path}/defaultMaterial``. """ + + +# Backward compatibility alias +PhysicsCfg = PhysicsCfg +""".. deprecated:: 2.4 + Use :class:`PhysicsCfg` instead. +""" diff --git a/source/isaaclab/isaaclab/sim/__init__.py b/source/isaaclab/isaaclab/sim/__init__.py index 3d8a73c28e9..9cb5fdc13aa 100644 --- a/source/isaaclab/isaaclab/sim/__init__.py +++ b/source/isaaclab/isaaclab/sim/__init__.py @@ -36,17 +36,17 @@ from .utils import * # noqa: F401, F403 from .views import * # noqa: F401, F403 -# Deprecated alias for PhysxCfg -> PhysxManagerCfg +# Deprecated alias for PhysxCfg -> PhysxCfg # This supports old code that uses `from isaaclab.sim import PhysxCfg` try: - from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg as _PhysxManagerCfg + from isaaclab_physx.physics import PhysxCfg as _PhysxCfg - class PhysxCfg(_PhysxManagerCfg): - """DEPRECATED: Use PhysxManagerCfg from isaaclab_physx.physics instead.""" + class PhysxCfg(_PhysxCfg): + """DEPRECATED: Use PhysxCfg from isaaclab_physx.physics instead.""" def __init__(self, *args, **kwargs): warnings.warn( - "PhysxCfg is deprecated. Use PhysxManagerCfg from isaaclab_physx.physics instead.", + "PhysxCfg is deprecated. Use PhysxCfg from isaaclab_physx.physics instead.", DeprecationWarning, stacklevel=2, ) diff --git a/source/isaaclab/isaaclab/sim/simulation_cfg.py b/source/isaaclab/isaaclab/sim/simulation_cfg.py index c679d0c89e4..71bb394f2e8 100644 --- a/source/isaaclab/isaaclab/sim/simulation_cfg.py +++ b/source/isaaclab/isaaclab/sim/simulation_cfg.py @@ -13,35 +13,20 @@ import warnings from typing import Any, Literal # Literal used by RenderCfg -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg -from isaaclab.physics.physics_manager_cfg import PhysicsManagerCfg +from isaaclab.physics import PhysicsCfg from isaaclab.utils import configclass from isaaclab.visualizers import VisualizerCfg - -# Deprecated alias for PhysxCfg -> PhysxManagerCfg -# This supports old code that uses `from isaaclab.sim.simulation_cfg import PhysxCfg` -class PhysxCfg(PhysxManagerCfg): - """DEPRECATED: Use PhysxManagerCfg from isaaclab_physx.physics instead.""" - - def __init__(self, *args, **kwargs): - warnings.warn( - "PhysxCfg is deprecated. Use PhysxManagerCfg from isaaclab_physx.physics instead.", - DeprecationWarning, - stacklevel=2, - ) - super().__init__(*args, **kwargs) - - -# Mapping of deprecated SimulationCfg fields to their new location in physics_manager_cfg +# Mapping of deprecated SimulationCfg fields to their new location in physics _DEPRECATED_FIELDS = { - "dt": "physics_manager_cfg.dt", - "gravity": "physics_manager_cfg.gravity", - "physics_prim_path": "physics_manager_cfg.physics_prim_path", - "physics_material": "physics_manager_cfg.physics_material", - "use_fabric": "physics_manager_cfg.use_fabric", - "physx": "physics_manager_cfg (PhysxManagerCfg attributes directly)", + "dt": "physics.dt", + "gravity": "physics.gravity", + "physics_prim_path": "physics.physics_prim_path", + "physics_material": "physics.physics_material", + "use_fabric": "physics.use_fabric", + "physx": "physics (PhysxCfg attributes directly)", } @@ -197,14 +182,14 @@ class SimulationCfg: """Configuration for simulation physics. .. note:: - The following fields have been moved to ``physics_manager_cfg`` and are deprecated: + The following fields have been moved to ``physics`` and are deprecated: - - ``dt`` → ``physics_manager_cfg.dt`` - - ``gravity`` → ``physics_manager_cfg.gravity`` - - ``physics_prim_path`` → ``physics_manager_cfg.physics_prim_path`` - - ``physics_material`` → ``physics_manager_cfg.physics_material`` - - ``use_fabric`` → ``physics_manager_cfg.use_fabric`` - - ``physx`` → Use ``PhysxManagerCfg`` attributes directly + - ``dt`` → ``physics.dt`` + - ``gravity`` → ``physics.gravity`` + - ``physics_prim_path`` → ``physics.physics_prim_path`` + - ``physics_material`` → ``physics.physics_material`` + - ``use_fabric`` → ``physics.use_fabric`` + - ``physx`` → Use ``PhysxCfg`` attributes directly Using the old field names will issue a deprecation warning and forward the values to the new location. @@ -238,8 +223,8 @@ class SimulationCfg: with the GUI enabled. This is to allow certain GUI features to work properly. """ - physics_manager_cfg: PhysicsManagerCfg = PhysxManagerCfg() - """Physics manager configuration. Default is PhysxManagerCfg(). + physics: PhysicsCfg = PhysxCfg() + """Physics manager configuration. Default is PhysxCfg(). This configuration determines which physics manager to use. Override with a different config (e.g., NewtonManagerCfg) to use a different physics backend. @@ -272,28 +257,28 @@ class SimulationCfg: # Deprecated fields - accepted in constructor for backward compatibility dt: float | None = None - """DEPRECATED: Use physics_manager_cfg.dt instead.""" + """DEPRECATED: Use physics.dt instead.""" gravity: tuple[float, float, float] | None = None - """DEPRECATED: Use physics_manager_cfg.gravity instead.""" + """DEPRECATED: Use physics.gravity instead.""" physics_prim_path: str | None = None - """DEPRECATED: Use physics_manager_cfg.physics_prim_path instead.""" + """DEPRECATED: Use physics.physics_prim_path instead.""" physics_material: Any | None = None - """DEPRECATED: Use physics_manager_cfg.physics_material instead.""" + """DEPRECATED: Use physics.physics_material instead.""" use_fabric: bool | None = None - """DEPRECATED: Use physics_manager_cfg.use_fabric instead.""" + """DEPRECATED: Use physics.use_fabric instead.""" physx: Any | None = None - """DEPRECATED: Use physics_manager_cfg (PhysxManagerCfg) directly instead. + """DEPRECATED: Use physics (PhysxCfg) directly instead. - After initialization, this field is set to physics_manager_cfg for backward compatibility. + After initialization, this field is set to physics for backward compatibility. """ def __post_init__(self): - """Forward deprecated constructor arguments to physics_manager_cfg.""" + """Forward deprecated constructor arguments to physics.""" deprecated_fields = ["dt", "gravity", "physics_prim_path", "physics_material", "use_fabric"] for field_name in deprecated_fields: @@ -302,13 +287,13 @@ def __post_init__(self): if value is not None: warnings.warn( f"SimulationCfg({field_name}=...) is deprecated. " - f"Use SimulationCfg(physics_manager_cfg=PhysxManagerCfg({field_name}=...)) instead.", - DeprecationWarning, + f"Use SimulationCfg(physics=PhysxCfg({field_name}=...)) instead.", + FutureWarning, stacklevel=4, ) - # Forward to physics_manager_cfg - if hasattr(self.physics_manager_cfg, field_name): - setattr(self.physics_manager_cfg, field_name, value) + # Forward to physics + if hasattr(self.physics, field_name): + setattr(self.physics, field_name, value) # Delete deprecated fields so __getattr__ is called when accessing them # This allows runtime access like self.sim.dt to work via __getattr__ @@ -317,18 +302,17 @@ def __post_init__(self): with contextlib.suppress(AttributeError): delattr(self, field_name) - # Set physics_material to point to physics_manager_cfg.physics_material for backward-compatible access - if hasattr(self.physics_manager_cfg, "physics_material"): - object.__setattr__(self, "physics_material", self.physics_manager_cfg.physics_material) + # Set physics_material to point to physics.physics_material for backward-compatible access + if hasattr(self.physics, "physics_material"): + object.__setattr__(self, "physics_material", self.physics.physics_material) - # Handle physx=PhysxCfg(...) - copy PhysX-specific attributes to physics_manager_cfg + # Handle physx=PhysxCfg(...) - copy PhysX-specific attributes to physics # The old PhysxCfg only had PhysX-specific settings, not dt/gravity/etc. physx_cfg = getattr(self, "physx", None) if physx_cfg is not None: warnings.warn( - "SimulationCfg(physx=...) is deprecated. " - "Use SimulationCfg(physics_manager_cfg=PhysxManagerCfg(...)) instead.", - DeprecationWarning, + "SimulationCfg(physx=...) is deprecated. Use SimulationCfg(physics=PhysxCfg(...)) instead.", + FutureWarning, stacklevel=4, ) # PhysX-specific fields that should be copied (not general physics settings) @@ -372,66 +356,74 @@ def __post_init__(self): else: default = None # Only copy if different from default - if value != default and hasattr(self.physics_manager_cfg, field.name): - setattr(self.physics_manager_cfg, field.name, value) + if value != default and hasattr(self.physics, field.name): + setattr(self.physics, field.name, value) - # Set physx to physics_manager_cfg for backward-compatible access (sim.physx.some_setting) - object.__setattr__(self, "physx", self.physics_manager_cfg) + # Note: 'physx' is handled in __getattr__ for backward-compatible access with deprecation warning + # Delete the physx field so __getattr__ is called when accessing it + with contextlib.suppress(AttributeError): + delattr(self, "physx") def __setattr__(self, name: str, value: Any) -> None: - """Intercept deprecated attribute assignment and forward to physics_manager_cfg.""" + """Intercept deprecated attribute assignment and forward to physics.""" # Mapping of deprecated fields to their new location deprecated_map = { - "dt": "physics_manager_cfg.dt", - "gravity": "physics_manager_cfg.gravity", - "physics_prim_path": "physics_manager_cfg.physics_prim_path", - "physics_material": "physics_manager_cfg.physics_material", - "use_fabric": "physics_manager_cfg.use_fabric", + "dt": "physics.dt", + "gravity": "physics.gravity", + "physics_prim_path": "physics.physics_prim_path", + "physics_material": "physics.physics_material", + "use_fabric": "physics.use_fabric", } if name in deprecated_map and value is not None: # Only forward non-None values (None means "not set" for deprecated fields) try: - physics_cfg = object.__getattribute__(self, "physics_manager_cfg") - if hasattr(physics_cfg, name): - setattr(physics_cfg, name, value) + physics = object.__getattribute__(self, "physics") + if hasattr(physics, name): + setattr(physics, name, value) warnings.warn( f"SimulationCfg.{name} is deprecated. Use {deprecated_map[name]} instead.", - DeprecationWarning, + FutureWarning, stacklevel=2, ) return except AttributeError: - # physics_manager_cfg not yet set, fall through to normal setattr + # physics not yet set, fall through to normal setattr pass # Default behavior object.__setattr__(self, name, value) def __getattr__(self, name: str) -> Any: - """Intercept deprecated attribute access and forward to physics_manager_cfg.""" + """Intercept deprecated attribute access and forward to physics.""" # Mapping of deprecated fields to their new location deprecated_map = { - "dt": "physics_manager_cfg.dt", - "gravity": "physics_manager_cfg.gravity", - "physics_prim_path": "physics_manager_cfg.physics_prim_path", - "physics_material": "physics_manager_cfg.physics_material", - "use_fabric": "physics_manager_cfg.use_fabric", + "dt": "physics.dt", + "gravity": "physics.gravity", + "physics_prim_path": "physics.physics_prim_path", + "physics_material": "physics.physics_material", + "use_fabric": "physics.use_fabric", } if name in deprecated_map: try: - physics_cfg = object.__getattribute__(self, "physics_manager_cfg") - if hasattr(physics_cfg, name): + physics = object.__getattribute__(self, "physics") + if hasattr(physics, name): warnings.warn( f"SimulationCfg.{name} is deprecated. Use {deprecated_map[name]} instead.", - DeprecationWarning, + FutureWarning, stacklevel=2, ) - return getattr(physics_cfg, name) + return getattr(physics, name) except AttributeError: pass - # Note: 'physx' is now a field set to physics_manager_cfg in __post_init__ - # for backward compatibility with sim.physx.some_setting access + # Handle 'physx' access for backward compatibility with sim.physx.some_setting + if name == "physx": + warnings.warn( + "SimulationCfg.physx is deprecated. Use physics directly instead.", + FutureWarning, + stacklevel=2, + ) + return object.__getattribute__(self, "physics") raise AttributeError(f"'{type(self).__name__}' object has no attribute '{name}'") diff --git a/source/isaaclab/isaaclab/sim/simulation_context.py b/source/isaaclab/isaaclab/sim/simulation_context.py index 72ed1904774..d2698ed9102 100644 --- a/source/isaaclab/isaaclab/sim/simulation_context.py +++ b/source/isaaclab/isaaclab/sim/simulation_context.py @@ -111,8 +111,8 @@ def __init__(self, cfg: SimulationCfg | None = None): # Initialize USD physics scene and physics manager self._init_usd_physics_scene() - self._physics_manager_cfg = self.cfg.physics_manager_cfg - self.physics_manager: type[PhysicsManager] = self._physics_manager_cfg.class_type + self._physics = self.cfg.physics + self.physics_manager: type[PhysicsManager] = self._physics.class_type self.physics_manager.initialize(self) # Initialize visualizers @@ -130,7 +130,7 @@ def __init__(self, cfg: SimulationCfg | None = None): def _init_usd_physics_scene(self) -> None: """Create and configure the USD physics scene.""" - cfg = self.cfg.physics_manager_cfg + cfg = self.cfg.physics with sim_utils.use_stage(self.stage): # Set stage conventions for metric units UsdGeom.SetStageUpAxis(self.stage, "Z") @@ -203,7 +203,7 @@ def get_physics_dt(self) -> float: def _init_visualizers(self) -> None: """Initialize visualizers based on config and settings.""" self._visualizers: list[Visualizer] = [] - self._viz_dt = self.cfg.physics_manager_cfg.dt * self.cfg.render_interval + self._viz_dt = self.cfg.physics.dt * self.cfg.render_interval # Determine which visualizers to create viz_str = "omniverse" # Default @@ -407,11 +407,11 @@ def build_simulation_context( stage_utils.create_new_stage() if sim_cfg is None: - from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg + from isaaclab_physx.physics import PhysxCfg gravity = (0.0, 0.0, -9.81) if gravity_enabled else (0.0, 0.0, 0.0) - physics_manager_cfg = PhysxManagerCfg(dt=dt, gravity=gravity) - sim_cfg = SimulationCfg(device=device, physics_manager_cfg=physics_manager_cfg) + physics = PhysxCfg(dt=dt, gravity=gravity) + sim_cfg = SimulationCfg(device=device, physics=physics) sim = SimulationContext(sim_cfg) diff --git a/source/isaaclab/test/app/test_non_headless_launch.py b/source/isaaclab/test/app/test_non_headless_launch.py index 03f591ea272..dedf6c5686e 100644 --- a/source/isaaclab/test/app/test_non_headless_launch.py +++ b/source/isaaclab/test/app/test_non_headless_launch.py @@ -20,7 +20,7 @@ """Rest everything follows.""" -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import AssetBaseCfg @@ -53,7 +53,7 @@ def run_simulator( @pytest.mark.isaacsim_ci def test_non_headless_launch(): # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.005)) + sim_cfg = sim_utils.SimulationCfg(physics=PhysxCfg(dt=0.005)) sim = sim_utils.SimulationContext(sim_cfg) # design scene scene_cfg = SensorsSceneCfg(num_envs=1, env_spacing=2.0) diff --git a/source/isaaclab/test/assets/check_external_force.py b/source/isaaclab/test/assets/check_external_force.py index 96a5213e200..e88131b1b32 100644 --- a/source/isaaclab/test/assets/check_external_force.py +++ b/source/isaaclab/test/assets/check_external_force.py @@ -37,7 +37,7 @@ """Rest everything follows.""" import torch -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import Articulation @@ -53,7 +53,7 @@ def main(): """Main function.""" # Load kit helper - sim = SimulationContext(sim_utils.SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.005))) + sim = SimulationContext(sim_utils.SimulationCfg(physics=PhysxCfg(dt=0.005))) # Set main camera sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) diff --git a/source/isaaclab/test/assets/check_fixed_base_assets.py b/source/isaaclab/test/assets/check_fixed_base_assets.py index ccd92739bef..1f5d25fcbce 100644 --- a/source/isaaclab/test/assets/check_fixed_base_assets.py +++ b/source/isaaclab/test/assets/check_fixed_base_assets.py @@ -34,7 +34,7 @@ import numpy as np import torch -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import Articulation @@ -144,7 +144,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim = sim_utils.SimulationContext(sim_utils.SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01))) + sim = sim_utils.SimulationContext(sim_utils.SimulationCfg(physics=PhysxCfg(dt=0.01))) # Set main camera sim.set_camera_view(eye=[2.5, 2.5, 2.5], target=[0.0, 0.0, 0.0]) # design scene diff --git a/source/isaaclab/test/controllers/test_differential_ik.py b/source/isaaclab/test/controllers/test_differential_ik.py index f2ec6851bdc..c60aec0412f 100644 --- a/source/isaaclab/test/controllers/test_differential_ik.py +++ b/source/isaaclab/test/controllers/test_differential_ik.py @@ -14,7 +14,7 @@ import pytest import torch -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg from isaacsim.core.cloner import GridCloner @@ -44,7 +44,7 @@ def sim(): # Constants num_envs = 1 # Load kit helper - sim_cfg = sim_utils.SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01)) + sim_cfg = sim_utils.SimulationCfg(physics=PhysxCfg(dt=0.01)) sim = sim_utils.SimulationContext(sim_cfg) # TODO: Remove this once we have a better way to handle this. sim._app_control_on_stop_handle = None diff --git a/source/isaaclab/test/controllers/test_operational_space.py b/source/isaaclab/test/controllers/test_operational_space.py index e4de98da4ba..70dd82eebd1 100644 --- a/source/isaaclab/test/controllers/test_operational_space.py +++ b/source/isaaclab/test/controllers/test_operational_space.py @@ -15,7 +15,7 @@ import pytest import torch from flaky import flaky -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg from isaacsim.core.cloner import GridCloner @@ -49,7 +49,7 @@ def sim(): # Constants num_envs = 16 # Load kit helper - sim_cfg = sim_utils.SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01)) + sim_cfg = sim_utils.SimulationCfg(physics=PhysxCfg(dt=0.01)) sim = sim_utils.SimulationContext(sim_cfg) # TODO: Remove this once we have a better way to handle this. sim._app_control_on_stop_handle = None diff --git a/source/isaaclab/test/devices/check_keyboard.py b/source/isaaclab/test/devices/check_keyboard.py index 99fcfa57507..69ce1e9e89d 100644 --- a/source/isaaclab/test/devices/check_keyboard.py +++ b/source/isaaclab/test/devices/check_keyboard.py @@ -23,7 +23,7 @@ import ctypes -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg from isaaclab.devices import Se3Keyboard, Se3KeyboardCfg from isaaclab.sim import SimulationCfg, SimulationContext @@ -42,7 +42,7 @@ def quit_cb(): def main(): # Load kit helper - sim = SimulationContext(SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01))) + sim = SimulationContext(SimulationCfg(physics=PhysxCfg(dt=0.01))) # Create teleoperation interface teleop_interface = Se3Keyboard(Se3KeyboardCfg(pos_sensitivity=0.1, rot_sensitivity=0.1)) diff --git a/source/isaaclab/test/envs/test_env_rendering_logic.py b/source/isaaclab/test/envs/test_env_rendering_logic.py index 6cc11e8505b..e20c4255387 100644 --- a/source/isaaclab/test/envs/test_env_rendering_logic.py +++ b/source/isaaclab/test/envs/test_env_rendering_logic.py @@ -15,7 +15,7 @@ import pytest import torch -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg from isaaclab_physx.visualizers import RenderMode import omni.usd @@ -49,9 +49,7 @@ class EnvCfg(ManagerBasedEnvCfg): decimation: int = 4 episode_length_s: float = 100.0 - sim: SimulationCfg = SimulationCfg( - render_interval=render_interval, physics_manager_cfg=PhysxManagerCfg(dt=0.005) - ) + sim: SimulationCfg = SimulationCfg(render_interval=render_interval, physics=PhysxCfg(dt=0.005)) scene: InteractiveSceneCfg = InteractiveSceneCfg(num_envs=1, env_spacing=1.0) actions: EmptyManagerCfg = EmptyManagerCfg() observations: EmptyManagerCfg = EmptyManagerCfg() @@ -68,9 +66,7 @@ class EnvCfg(ManagerBasedRLEnvCfg): decimation: int = 4 episode_length_s: float = 100.0 - sim: SimulationCfg = SimulationCfg( - render_interval=render_interval, physics_manager_cfg=PhysxManagerCfg(dt=0.005) - ) + sim: SimulationCfg = SimulationCfg(render_interval=render_interval, physics=PhysxCfg(dt=0.005)) scene: InteractiveSceneCfg = InteractiveSceneCfg(num_envs=1, env_spacing=1.0) actions: EmptyManagerCfg = EmptyManagerCfg() observations: EmptyManagerCfg = EmptyManagerCfg() @@ -91,9 +87,7 @@ class EnvCfg(DirectRLEnvCfg): action_space: int = 0 observation_space: int = 0 episode_length_s: float = 100.0 - sim: SimulationCfg = SimulationCfg( - render_interval=render_interval, physics_manager_cfg=PhysxManagerCfg(dt=0.005) - ) + sim: SimulationCfg = SimulationCfg(render_interval=render_interval, physics=PhysxCfg(dt=0.005)) scene: InteractiveSceneCfg = InteractiveSceneCfg(num_envs=1, env_spacing=1.0) class Env(DirectRLEnv): diff --git a/source/isaaclab/test/managers/test_observation_manager.py b/source/isaaclab/test/managers/test_observation_manager.py index 5285d31f818..b135b0ecce5 100644 --- a/source/isaaclab/test/managers/test_observation_manager.py +++ b/source/isaaclab/test/managers/test_observation_manager.py @@ -20,7 +20,7 @@ import pytest import torch -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.managers import ( @@ -108,7 +108,7 @@ def setup_env(): num_envs = 20 device = "cuda:0" # set up sim - sim_cfg = sim_utils.SimulationCfg(device=device, physics_manager_cfg=PhysxManagerCfg(dt=dt)) + sim_cfg = sim_utils.SimulationCfg(device=device, physics=PhysxCfg(dt=dt)) sim = sim_utils.SimulationContext(sim_cfg) # create dummy environment env = namedtuple("ManagerBasedEnv", ["num_envs", "device", "data", "dt", "sim"])( diff --git a/source/isaaclab/test/markers/check_markers_visibility.py b/source/isaaclab/test/markers/check_markers_visibility.py index 84090d4cea9..40b1d85a15a 100644 --- a/source/isaaclab/test/markers/check_markers_visibility.py +++ b/source/isaaclab/test/markers/check_markers_visibility.py @@ -38,7 +38,7 @@ """Rest everything follows.""" -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import ArticulationCfg, AssetBaseCfg @@ -131,7 +131,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.005)) + sim_cfg = sim_utils.SimulationCfg(physics=PhysxCfg(dt=0.005)) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) diff --git a/source/isaaclab/test/markers/test_visualization_markers.py b/source/isaaclab/test/markers/test_visualization_markers.py index 158d02ed114..096cf2210ad 100644 --- a/source/isaaclab/test/markers/test_visualization_markers.py +++ b/source/isaaclab/test/markers/test_visualization_markers.py @@ -14,7 +14,7 @@ import pytest import torch -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.markers import VisualizationMarkers, VisualizationMarkersCfg @@ -32,7 +32,7 @@ def sim(): # Open a new stage sim_utils.create_new_stage() # Load kit helper - sim_context = SimulationContext(SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=dt))) + sim_context = SimulationContext(SimulationCfg(physics=PhysxCfg(dt=dt))) yield sim_context # Cleanup sim_context._disable_app_control_on_stop_handle = True # prevent timeout diff --git a/source/isaaclab/test/scene/check_interactive_scene.py b/source/isaaclab/test/scene/check_interactive_scene.py index c2635d6b8fa..f7824c41576 100644 --- a/source/isaaclab/test/scene/check_interactive_scene.py +++ b/source/isaaclab/test/scene/check_interactive_scene.py @@ -27,7 +27,7 @@ """Rest everything follows.""" -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import AssetBaseCfg @@ -82,7 +82,7 @@ def main(): """Main function.""" # Load kit helper - sim = SimulationContext(sim_utils.SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.005))) + sim = SimulationContext(sim_utils.SimulationCfg(physics=PhysxCfg(dt=0.005))) # Set main camera sim.set_camera_view(eye=[5, 5, 5], target=[0.0, 0.0, 0.0]) diff --git a/source/isaaclab/test/sensors/test_camera.py b/source/isaaclab/test/sensors/test_camera.py index 66abc398f87..967dcc88818 100644 --- a/source/isaaclab/test/sensors/test_camera.py +++ b/source/isaaclab/test/sensors/test_camera.py @@ -23,7 +23,7 @@ import pytest import scipy.spatial.transform as tf import torch -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import omni.replicator.core as rep from pxr import Gf, Usd, UsdGeom @@ -63,7 +63,7 @@ def setup() -> tuple[sim_utils.SimulationContext, CameraCfg, float]: # Simulation time-step dt = 0.01 # Load kit helper - sim_cfg = sim_utils.SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=dt)) + sim_cfg = sim_utils.SimulationCfg(physics=PhysxCfg(dt=dt)) sim = sim_utils.SimulationContext(sim_cfg) # populate scene _populate_scene() diff --git a/source/isaaclab/test/sensors/test_multi_mesh_ray_caster_camera.py b/source/isaaclab/test/sensors/test_multi_mesh_ray_caster_camera.py index 31b08e9d36c..57301e82d16 100644 --- a/source/isaaclab/test/sensors/test_multi_mesh_ray_caster_camera.py +++ b/source/isaaclab/test/sensors/test_multi_mesh_ray_caster_camera.py @@ -21,7 +21,7 @@ import numpy as np import pytest import torch -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import omni.replicator.core as rep from pxr import Gf @@ -50,7 +50,7 @@ def setup_simulation(): # Simulation time-step dt = 0.01 # Load kit helper - sim_cfg = sim_utils.SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=dt)) + sim_cfg = sim_utils.SimulationCfg(physics=PhysxCfg(dt=dt)) sim: sim_utils.SimulationContext = sim_utils.SimulationContext(sim_cfg) # Ground-plane mesh = make_plane(size=(100, 100), height=0.0, center_zero=True) diff --git a/source/isaaclab/test/sensors/test_multi_tiled_camera.py b/source/isaaclab/test/sensors/test_multi_tiled_camera.py index 3b619160a3a..4b332ae2921 100644 --- a/source/isaaclab/test/sensors/test_multi_tiled_camera.py +++ b/source/isaaclab/test/sensors/test_multi_tiled_camera.py @@ -22,7 +22,7 @@ import pytest import torch from flaky import flaky -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import omni.replicator.core as rep from pxr import Gf, UsdGeom @@ -50,7 +50,7 @@ def setup_camera(): # Simulation time-step dt = 0.01 # Load kit helper - sim_cfg = sim_utils.SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=dt)) + sim_cfg = sim_utils.SimulationCfg(physics=PhysxCfg(dt=dt)) sim = sim_utils.SimulationContext(sim_cfg) # populate scene _populate_scene() diff --git a/source/isaaclab/test/sensors/test_ray_caster_camera.py b/source/isaaclab/test/sensors/test_ray_caster_camera.py index 5148bfe5bed..ea90338004d 100644 --- a/source/isaaclab/test/sensors/test_ray_caster_camera.py +++ b/source/isaaclab/test/sensors/test_ray_caster_camera.py @@ -21,7 +21,7 @@ import numpy as np import pytest import torch -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import omni.replicator.core as rep from pxr import Gf @@ -70,7 +70,7 @@ def setup() -> tuple[sim_utils.SimulationContext, RayCasterCameraCfg, float]: # Simulation time-step dt = 0.01 # Load kit helper - sim_cfg = sim_utils.SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=dt)) + sim_cfg = sim_utils.SimulationCfg(physics=PhysxCfg(dt=dt)) sim = sim_utils.SimulationContext(sim_cfg) # Ground-plane mesh = make_plane(size=(100, 100), height=0.0, center_zero=True) diff --git a/source/isaaclab/test/sensors/test_sensor_base.py b/source/isaaclab/test/sensors/test_sensor_base.py index 81fa3badefa..12c9236bf28 100644 --- a/source/isaaclab/test/sensors/test_sensor_base.py +++ b/source/isaaclab/test/sensors/test_sensor_base.py @@ -19,7 +19,7 @@ import pytest import torch -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.sensors import SensorBase, SensorBaseCfg @@ -94,7 +94,7 @@ def create_dummy_sensor(request, device): # Simulation time-step dt = 0.01 # Load kit helper - sim_cfg = sim_utils.SimulationCfg(device=device, physics_manager_cfg=PhysxManagerCfg(dt=dt)) + sim_cfg = sim_utils.SimulationCfg(device=device, physics=PhysxCfg(dt=dt)) sim = sim_utils.SimulationContext(sim_cfg) # create sensor diff --git a/source/isaaclab/test/sensors/test_tiled_camera.py b/source/isaaclab/test/sensors/test_tiled_camera.py index 8b16be1257f..9ad199798dc 100644 --- a/source/isaaclab/test/sensors/test_tiled_camera.py +++ b/source/isaaclab/test/sensors/test_tiled_camera.py @@ -21,7 +21,7 @@ import numpy as np import pytest import torch -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import omni.replicator.core as rep from pxr import Gf, UsdGeom @@ -51,7 +51,7 @@ def setup_camera(device) -> tuple[sim_utils.SimulationContext, TiledCameraCfg, f # Simulation time-step dt = 0.01 # Load kit helper - sim_cfg = sim_utils.SimulationCfg(device=device, physics_manager_cfg=PhysxManagerCfg(dt=dt)) + sim_cfg = sim_utils.SimulationCfg(device=device, physics=PhysxCfg(dt=dt)) sim: sim_utils.SimulationContext = sim_utils.SimulationContext(sim_cfg) # populate scene _populate_scene() diff --git a/source/isaaclab/test/sim/check_meshes.py b/source/isaaclab/test/sim/check_meshes.py index a68adda0f71..f79ac4a30a8 100644 --- a/source/isaaclab/test/sim/check_meshes.py +++ b/source/isaaclab/test/sim/check_meshes.py @@ -40,7 +40,7 @@ import numpy as np import torch import tqdm -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils @@ -142,7 +142,7 @@ def design_scene(): def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01)) + sim_cfg = sim_utils.SimulationCfg(physics=PhysxCfg(dt=0.01)) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view([8.0, 8.0, 6.0], [0.0, 0.0, 0.0]) 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 80ad3a5a5bc..332b40d8471 100644 --- a/source/isaaclab/test/sim/test_build_simulation_context_headless.py +++ b/source/isaaclab/test/sim/test_build_simulation_context_headless.py @@ -36,12 +36,12 @@ def test_build_simulation_context_no_cfg(gravity_enabled, device, dt): """Test that the simulation context is built when no simulation cfg is passed in.""" with build_simulation_context(gravity_enabled=gravity_enabled, device=device, dt=dt) as sim: if gravity_enabled: - assert sim.cfg.physics_manager_cfg.gravity == (0.0, 0.0, -9.81) + assert sim.cfg.physics.gravity == (0.0, 0.0, -9.81) else: - assert sim.cfg.physics_manager_cfg.gravity == (0.0, 0.0, 0.0) + assert sim.cfg.physics.gravity == (0.0, 0.0, 0.0) assert sim.cfg.device == device - assert sim.cfg.physics_manager_cfg.dt == dt + assert sim.cfg.physics.dt == dt # Ensure that dome light didn't get added automatically as we are headless assert not sim.stage.GetPrimAtPath("/World/defaultDomeLight").IsValid() @@ -76,7 +76,7 @@ def test_build_simulation_context_auto_add_lighting(add_lighting, auto_add_light @pytest.mark.isaacsim_ci def test_build_simulation_context_cfg(): """Test that the simulation context is built with the correct cfg and values don't get overridden.""" - from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg + from isaaclab_physx.physics import PhysxCfg dt = 0.001 # Non-standard gravity @@ -85,7 +85,7 @@ def test_build_simulation_context_cfg(): cfg = SimulationCfg( device=device, - physics_manager_cfg=PhysxManagerCfg( + physics=PhysxCfg( gravity=gravity, dt=dt, ), @@ -93,6 +93,6 @@ def test_build_simulation_context_cfg(): with build_simulation_context(sim_cfg=cfg, gravity_enabled=False, dt=0.01, device="cpu") as sim: # Values from sim_cfg should not be overridden by build_simulation_context args - assert sim.cfg.physics_manager_cfg.gravity == gravity + assert sim.cfg.physics.gravity == gravity assert sim.cfg.device == device - assert sim.cfg.physics_manager_cfg.dt == dt + assert sim.cfg.physics.dt == dt diff --git a/source/isaaclab/test/sim/test_build_simulation_context_nonheadless.py b/source/isaaclab/test/sim/test_build_simulation_context_nonheadless.py index 57884a3a77c..e1958ab5b83 100644 --- a/source/isaaclab/test/sim/test_build_simulation_context_nonheadless.py +++ b/source/isaaclab/test/sim/test_build_simulation_context_nonheadless.py @@ -34,12 +34,12 @@ def test_build_simulation_context_no_cfg(gravity_enabled, device, dt): """Test that the simulation context is built when no simulation cfg is passed in.""" with build_simulation_context(gravity_enabled=gravity_enabled, device=device, dt=dt) as sim: if gravity_enabled: - assert sim.cfg.physics_manager_cfg.gravity == (0.0, 0.0, -9.81) + assert sim.cfg.physics.gravity == (0.0, 0.0, -9.81) else: - assert sim.cfg.physics_manager_cfg.gravity == (0.0, 0.0, 0.0) + assert sim.cfg.physics.gravity == (0.0, 0.0, 0.0) assert sim.cfg.device == device - assert sim.cfg.physics_manager_cfg.dt == dt + assert sim.cfg.physics.dt == dt @pytest.mark.parametrize("add_ground_plane", [True, False]) @@ -71,7 +71,7 @@ def test_build_simulation_context_auto_add_lighting(add_lighting, auto_add_light def test_build_simulation_context_cfg(): """Test that the simulation context is built with the correct cfg and values don't get overridden.""" - from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg + from isaaclab_physx.physics import PhysxCfg dt = 0.001 # Non-standard gravity @@ -80,7 +80,7 @@ def test_build_simulation_context_cfg(): cfg = SimulationCfg( device=device, - physics_manager_cfg=PhysxManagerCfg( + physics=PhysxCfg( gravity=gravity, dt=dt, ), @@ -88,6 +88,6 @@ def test_build_simulation_context_cfg(): with build_simulation_context(sim_cfg=cfg, gravity_enabled=False, dt=0.01, device="cpu") as sim: # Values from sim_cfg should not be overridden by build_simulation_context args - assert sim.cfg.physics_manager_cfg.gravity == gravity + assert sim.cfg.physics.gravity == gravity assert sim.cfg.device == device - assert sim.cfg.physics_manager_cfg.dt == dt + assert sim.cfg.physics.dt == dt diff --git a/source/isaaclab/test/sim/test_mesh_converter.py b/source/isaaclab/test/sim/test_mesh_converter.py index 731fc4ded5a..e08d59f82a8 100644 --- a/source/isaaclab/test/sim/test_mesh_converter.py +++ b/source/isaaclab/test/sim/test_mesh_converter.py @@ -18,7 +18,7 @@ import tempfile import pytest -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import omni from pxr import UsdGeom, UsdPhysics @@ -67,7 +67,7 @@ def sim(): # Simulation time-step dt = 0.01 # Load kit helper - sim = SimulationContext(SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=dt))) + sim = SimulationContext(SimulationCfg(physics=PhysxCfg(dt=dt))) yield sim # stop simulation sim.stop() diff --git a/source/isaaclab/test/sim/test_mjcf_converter.py b/source/isaaclab/test/sim/test_mjcf_converter.py index d18f9250ba6..675fb878eac 100644 --- a/source/isaaclab/test/sim/test_mjcf_converter.py +++ b/source/isaaclab/test/sim/test_mjcf_converter.py @@ -15,7 +15,7 @@ import os import pytest -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg from isaacsim.core.utils.extensions import enable_extension, get_extension_path_from_name @@ -32,7 +32,7 @@ def test_setup_teardown(): # Setup: Create simulation context dt = 0.01 - sim = SimulationContext(SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=dt))) + sim = SimulationContext(SimulationCfg(physics=PhysxCfg(dt=dt))) # Setup: Create MJCF config enable_extension("isaacsim.asset.importer.mjcf") diff --git a/source/isaaclab/test/sim/test_schemas.py b/source/isaaclab/test/sim/test_schemas.py index 54447d7d777..8686e93d415 100644 --- a/source/isaaclab/test/sim/test_schemas.py +++ b/source/isaaclab/test/sim/test_schemas.py @@ -15,7 +15,7 @@ import math import pytest -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg from pxr import UsdPhysics @@ -34,7 +34,7 @@ def setup_simulation(): # Simulation time-step dt = 0.1 # Load kit helper - sim = SimulationContext(SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=dt))) + sim = SimulationContext(SimulationCfg(physics=PhysxCfg(dt=dt))) # 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 d8d45c21647..0d9bb6700c6 100644 --- a/source/isaaclab/test/sim/test_simulation_context.py +++ b/source/isaaclab/test/sim/test_simulation_context.py @@ -16,7 +16,7 @@ import numpy as np import pytest -from isaaclab_physx.physics import IsaacEvents, PhysxManager, PhysxManagerCfg +from isaaclab_physx.physics import IsaacEvents, PhysxCfg, PhysxManager import omni.timeline @@ -48,12 +48,12 @@ def test_init(device): """Test the simulation context initialization.""" from isaaclab.sim.spawners.materials import RigidBodyMaterialCfg - physics_manager_cfg = PhysxManagerCfg( + physics = PhysxCfg( physics_prim_path="/Physics/PhysX", gravity=(0.0, -0.5, -0.5), physics_material=RigidBodyMaterialCfg(), ) - cfg = SimulationCfg(device=device, physics_manager_cfg=physics_manager_cfg, render_interval=5) + cfg = SimulationCfg(device=device, physics=physics, render_interval=5) # sim = SimulationContext(cfg) # TODO: Figure out why keyword argument doesn't work. # note: added a fix in Isaac Sim 2023.1 for this. @@ -78,7 +78,7 @@ def test_init(device): # check valid settings physics_hz = physx_scene_api.GetTimeStepsPerSecondAttr().Get() physics_dt = 1.0 / physics_hz - assert physics_dt == cfg.physics_manager_cfg.dt + assert physics_dt == cfg.physics.dt # check valid paths assert sim.stage.GetPrimAtPath("/Physics/PhysX").IsValid() @@ -89,7 +89,7 @@ def test_init(device): physics_scene.GetGravityMagnitudeAttr().Get(), ) gravity = np.array(gravity_dir) * gravity_mag - np.testing.assert_almost_equal(gravity, cfg.physics_manager_cfg.gravity) + np.testing.assert_almost_equal(gravity, cfg.physics.gravity) @pytest.mark.isaacsim_ci @@ -195,7 +195,7 @@ def test_timeline_pause(): @pytest.mark.isaacsim_ci def test_reset(): """Test simulation reset.""" - cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01)) + cfg = SimulationCfg(physics=PhysxCfg(dt=0.01)) sim = SimulationContext(cfg) # create a simple cube to test with @@ -215,7 +215,7 @@ def test_reset(): @pytest.mark.isaacsim_ci def test_reset_soft(): """Test soft reset (without stopping simulation).""" - cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01)) + cfg = SimulationCfg(physics=PhysxCfg(dt=0.01)) sim = SimulationContext(cfg) # create a simple cube @@ -236,7 +236,7 @@ def test_reset_soft(): @pytest.mark.isaacsim_ci def test_forward(): """Test forward propagation for fabric updates.""" - cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01, use_fabric=True)) + cfg = SimulationCfg(physics=PhysxCfg(dt=0.01, use_fabric=True)) sim = SimulationContext(cfg) # create simple scene @@ -256,7 +256,7 @@ def test_forward(): @pytest.mark.parametrize("render", [True, False]) def test_step(render): """Test stepping simulation with and without rendering.""" - cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01)) + cfg = SimulationCfg(physics=PhysxCfg(dt=0.01)) sim = SimulationContext(cfg) # create simple scene @@ -276,7 +276,7 @@ def test_step(render): @pytest.mark.isaacsim_ci def test_render(): """Test rendering simulation.""" - cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01)) + cfg = SimulationCfg(physics=PhysxCfg(dt=0.01)) sim = SimulationContext(cfg) # create simple scene @@ -333,7 +333,7 @@ def test_clear_stage(): assert not sim.stage.GetPrimAtPath("/World/Cube1").IsValid() assert not sim.stage.GetPrimAtPath("/World/Cube2").IsValid() assert sim.stage.GetPrimAtPath("/World").IsValid() - assert sim.stage.GetPrimAtPath(sim.cfg.physics_manager_cfg.physics_prim_path).IsValid() # type: ignore[union-attr] + assert sim.stage.GetPrimAtPath(sim.cfg.physics.physics_prim_path).IsValid() # type: ignore[union-attr] """ @@ -347,11 +347,11 @@ def test_solver_type(solver_type): """Test different solver types.""" from pxr.PhysxSchema import PhysxSceneAPI - cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(solver_type=solver_type)) + cfg = SimulationCfg(physics=PhysxCfg(solver_type=solver_type)) sim = SimulationContext(cfg) # obtain physics scene api from USD - physics_scene_prim = sim.stage.GetPrimAtPath(cfg.physics_manager_cfg.physics_prim_path) + physics_scene_prim = sim.stage.GetPrimAtPath(cfg.physics.physics_prim_path) physx_scene_api = PhysxSceneAPI(physics_scene_prim) # check solver type is set solver_type_str = "PGS" if solver_type == 0 else "TGS" @@ -362,7 +362,7 @@ def test_solver_type(solver_type): @pytest.mark.parametrize("use_fabric", [True, False]) def test_fabric_setting(use_fabric): """Test that fabric setting is properly set.""" - cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(use_fabric=use_fabric)) + cfg = SimulationCfg(physics=PhysxCfg(use_fabric=use_fabric)) sim = SimulationContext(cfg) # check fabric is enabled via physics setting @@ -375,11 +375,11 @@ def test_physics_dt(dt): """Test that physics time step is properly configured.""" from pxr.PhysxSchema import PhysxSceneAPI - cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=dt)) + cfg = SimulationCfg(physics=PhysxCfg(dt=dt)) sim = SimulationContext(cfg) # obtain physics scene api from USD - physics_scene_prim = sim.stage.GetPrimAtPath(cfg.physics_manager_cfg.physics_prim_path) + physics_scene_prim = sim.stage.GetPrimAtPath(cfg.physics.physics_prim_path) physx_scene_api = PhysxSceneAPI(physics_scene_prim) # check physics dt physics_hz = physx_scene_api.GetTimeStepsPerSecondAttr().Get() @@ -393,11 +393,11 @@ def test_custom_gravity(gravity): """Test that gravity can be properly set.""" from pxr import UsdPhysics - cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(gravity=gravity)) + cfg = SimulationCfg(physics=PhysxCfg(gravity=gravity)) sim = SimulationContext(cfg) # obtain physics scene from USD - physics_scene_prim = sim.stage.GetPrimAtPath(cfg.physics_manager_cfg.physics_prim_path) + physics_scene_prim = sim.stage.GetPrimAtPath(cfg.physics.physics_prim_path) physics_scene = UsdPhysics.Scene(physics_scene_prim) gravity_dir, gravity_mag = ( @@ -405,7 +405,7 @@ def test_custom_gravity(gravity): physics_scene.GetGravityMagnitudeAttr().Get(), ) actual_gravity = np.array(gravity_dir) * gravity_mag - np.testing.assert_almost_equal(actual_gravity, cfg.physics_manager_cfg.gravity, decimal=6) + np.testing.assert_almost_equal(actual_gravity, cfg.physics.gravity, decimal=6) """ @@ -416,7 +416,7 @@ def test_custom_gravity(gravity): @pytest.mark.isaacsim_ci def test_timeline_callbacks_on_play(): """Test that timeline callbacks are triggered on play event.""" - cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01)) + cfg = SimulationCfg(physics=PhysxCfg(dt=0.01)) sim = SimulationContext(cfg) # create a simple scene @@ -478,7 +478,7 @@ def on_stop_callback(event): def test_timeline_callbacks_with_weakref(): """Test that timeline callbacks work correctly with weak references (similar to asset_base.py).""" - cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01)) + cfg = SimulationCfg(physics=PhysxCfg(dt=0.01)) sim = SimulationContext(cfg) # create a simple scene @@ -565,7 +565,7 @@ def safe_callback(callback_name, event, obj_ref): @pytest.mark.isaacsim_ci def test_multiple_callbacks_on_same_event(): """Test that multiple callbacks can be registered for the same event.""" - cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01)) + cfg = SimulationCfg(physics=PhysxCfg(dt=0.01)) sim = SimulationContext(cfg) # create tracking for multiple callbacks @@ -617,7 +617,7 @@ def callback3(event): @pytest.mark.isaacsim_ci def test_callback_execution_order(): """Test that callbacks are executed in the correct order based on priority.""" - cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01)) + cfg = SimulationCfg(physics=PhysxCfg(dt=0.01)) sim = SimulationContext(cfg) # track execution order @@ -667,7 +667,7 @@ def callback_high_priority(event): @pytest.mark.isaacsim_ci def test_callback_unsubscribe(): """Test that unsubscribing callbacks works correctly.""" - cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01)) + cfg = SimulationCfg(physics=PhysxCfg(dt=0.01)) sim = SimulationContext(cfg) # create callback counter @@ -710,7 +710,7 @@ def on_play_callback(event): @pytest.mark.isaacsim_ci def test_pause_event_callback(): """Test that pause event callbacks are triggered correctly.""" - cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01)) + cfg = SimulationCfg(physics=PhysxCfg(dt=0.01)) sim = SimulationContext(cfg) # create callback tracker @@ -754,7 +754,7 @@ def on_pause_callback(event): ) def test_isaac_event_triggered_on_reset(event_type): """Test that Isaac events are triggered during reset.""" - cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01)) + cfg = SimulationCfg(physics=PhysxCfg(dt=0.01)) sim = SimulationContext(cfg) # create simple scene @@ -789,7 +789,7 @@ def on_event(event): @pytest.mark.isaacsim_ci def test_isaac_event_prim_deletion(): """Test that PRIM_DELETION Isaac event is triggered when a prim is deleted.""" - cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01)) + cfg = SimulationCfg(physics=PhysxCfg(dt=0.01)) sim = SimulationContext(cfg) # create simple scene @@ -832,7 +832,7 @@ def on_prim_deletion(event): @pytest.mark.isaacsim_ci def test_isaac_event_timeline_stop(): """Test that TIMELINE_STOP Isaac event can be registered and triggered.""" - cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01)) + cfg = SimulationCfg(physics=PhysxCfg(dt=0.01)) sim = SimulationContext(cfg) # create callback tracker @@ -872,7 +872,7 @@ def on_timeline_stop(event): @pytest.mark.isaacsim_ci def test_isaac_event_callbacks_with_weakref(): """Test Isaac event callbacks with weak references (similar to asset_base.py pattern).""" - cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01)) + cfg = SimulationCfg(physics=PhysxCfg(dt=0.01)) sim = SimulationContext(cfg) # create simple scene @@ -946,7 +946,7 @@ def safe_callback(callback_name, event, obj_ref): @pytest.mark.isaacsim_ci def test_multiple_isaac_event_callbacks(): """Test that multiple callbacks can be registered for the same Isaac event.""" - cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01)) + cfg = SimulationCfg(physics=PhysxCfg(dt=0.01)) sim = SimulationContext(cfg) # create simple scene @@ -1000,7 +1000,7 @@ def callback3(event): @pytest.mark.isaacsim_ci def test_exception_in_callback_on_reset(): """Test that exceptions stored during reset are raised.""" - cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01)) + cfg = SimulationCfg(physics=PhysxCfg(dt=0.01)) sim = SimulationContext(cfg) # create simple scene @@ -1026,7 +1026,7 @@ def failing_callback(event): @pytest.mark.isaacsim_ci def test_exception_in_callback_on_step(): """Test that exceptions stored during step are raised.""" - cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01)) + cfg = SimulationCfg(physics=PhysxCfg(dt=0.01)) sim = SimulationContext(cfg) # create simple scene diff --git a/source/isaaclab/test/sim/test_spawn_from_files.py b/source/isaaclab/test/sim/test_spawn_from_files.py index 33bdb3e887a..787c1719680 100644 --- a/source/isaaclab/test/sim/test_spawn_from_files.py +++ b/source/isaaclab/test/sim/test_spawn_from_files.py @@ -13,7 +13,7 @@ """Rest everything follows.""" import pytest -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg from packaging.version import Version import omni.kit.app @@ -32,7 +32,7 @@ def sim(): # Simulation time-step dt = 0.1 # Load kit helper - sim = SimulationContext(SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=dt))) + sim = SimulationContext(SimulationCfg(physics=PhysxCfg(dt=dt))) # Wait for spawning sim_utils.update_stage() diff --git a/source/isaaclab/test/sim/test_spawn_lights.py b/source/isaaclab/test/sim/test_spawn_lights.py index a2676b8887c..8bda2100d9e 100644 --- a/source/isaaclab/test/sim/test_spawn_lights.py +++ b/source/isaaclab/test/sim/test_spawn_lights.py @@ -14,7 +14,7 @@ import pytest -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg from pxr import Usd, UsdLux @@ -31,7 +31,7 @@ def sim(): # Simulation time-step dt = 0.1 # Load kit helper - sim = SimulationContext(SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=dt))) + sim = SimulationContext(SimulationCfg(physics=PhysxCfg(dt=dt))) # Wait for spawning sim_utils.update_stage() diff --git a/source/isaaclab/test/sim/test_spawn_materials.py b/source/isaaclab/test/sim/test_spawn_materials.py index 0ef1b81e101..9f462381f22 100644 --- a/source/isaaclab/test/sim/test_spawn_materials.py +++ b/source/isaaclab/test/sim/test_spawn_materials.py @@ -14,7 +14,7 @@ import pytest -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg from pxr import UsdPhysics, UsdShade @@ -28,7 +28,7 @@ def sim(): """Create a simulation context.""" sim_utils.create_new_stage() dt = 0.1 - sim = SimulationContext(SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=dt))) + sim = SimulationContext(SimulationCfg(physics=PhysxCfg(dt=dt))) sim_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 c76f5118bd6..60e3bd83e3e 100644 --- a/source/isaaclab/test/sim/test_spawn_meshes.py +++ b/source/isaaclab/test/sim/test_spawn_meshes.py @@ -14,7 +14,7 @@ import pytest -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.sim import SimulationCfg, SimulationContext @@ -28,7 +28,7 @@ def sim(): # Simulation time-step dt = 0.1 # Load kit helper - sim = SimulationContext(SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=dt))) + sim = SimulationContext(SimulationCfg(physics=PhysxCfg(dt=dt))) # Wait for spawning sim_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 3a582a8670a..e4be4a42132 100644 --- a/source/isaaclab/test/sim/test_spawn_sensors.py +++ b/source/isaaclab/test/sim/test_spawn_sensors.py @@ -14,7 +14,7 @@ import pytest -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg from pxr import Usd @@ -29,7 +29,7 @@ def sim(): """Create a simulation context.""" sim_utils.create_new_stage() dt = 0.1 - sim = SimulationContext(SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=dt))) + sim = SimulationContext(SimulationCfg(physics=PhysxCfg(dt=dt))) sim_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 a5650b5c4ce..d6e42d2961f 100644 --- a/source/isaaclab/test/sim/test_spawn_shapes.py +++ b/source/isaaclab/test/sim/test_spawn_shapes.py @@ -13,7 +13,7 @@ """Rest everything follows.""" import pytest -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.sim import SimulationCfg, SimulationContext @@ -24,7 +24,7 @@ def sim(): """Create a simulation context.""" sim_utils.create_new_stage() dt = 0.1 - sim = SimulationContext(SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=dt))) + sim = SimulationContext(SimulationCfg(physics=PhysxCfg(dt=dt))) sim_utils.update_stage() yield sim sim._disable_app_control_on_stop_handle = True # prevent timeout diff --git a/source/isaaclab/test/sim/test_spawn_wrappers.py b/source/isaaclab/test/sim/test_spawn_wrappers.py index 10bf2c316a0..575bfcbf327 100644 --- a/source/isaaclab/test/sim/test_spawn_wrappers.py +++ b/source/isaaclab/test/sim/test_spawn_wrappers.py @@ -14,7 +14,7 @@ import pytest -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.sim import SimulationCfg, SimulationContext @@ -26,7 +26,7 @@ def sim(): """Create a simulation context.""" sim_utils.create_new_stage() dt = 0.1 - sim = SimulationContext(SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=dt))) + sim = SimulationContext(SimulationCfg(physics=PhysxCfg(dt=dt))) sim_utils.update_stage() yield sim sim.stop() diff --git a/source/isaaclab/test/sim/test_urdf_converter.py b/source/isaaclab/test/sim/test_urdf_converter.py index ca136fd9f97..2fae220259c 100644 --- a/source/isaaclab/test/sim/test_urdf_converter.py +++ b/source/isaaclab/test/sim/test_urdf_converter.py @@ -16,7 +16,7 @@ import numpy as np import pytest -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg from packaging.version import Version import omni.kit.app @@ -54,7 +54,7 @@ def sim_config(): # Simulation time-step dt = 0.01 # Load kit helper - sim = SimulationContext(SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=dt))) + sim = SimulationContext(SimulationCfg(physics=PhysxCfg(dt=dt))) yield sim, config # Teardown sim._disable_app_control_on_stop_handle = True # prevent timeout diff --git a/source/isaaclab/test/sim/test_views_xform_prim.py b/source/isaaclab/test/sim/test_views_xform_prim.py index ed5758a7326..afa8a53f505 100644 --- a/source/isaaclab/test/sim/test_views_xform_prim.py +++ b/source/isaaclab/test/sim/test_views_xform_prim.py @@ -20,7 +20,7 @@ except (ModuleNotFoundError, ImportError): _IsaacSimXformPrimView = None -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg # noqa: E402 +from isaaclab_physx.physics import PhysxCfg # noqa: E402 import isaaclab.sim as sim_utils # noqa: E402 from isaaclab.sim.views import XformPrimView as XformPrimView # noqa: E402 @@ -75,9 +75,7 @@ def _prim_type_for_backend(backend: str) -> str: def _create_view(pattern: str, device: str, backend: str) -> XformPrimView: """Create an XformPrimView for the requested backend.""" if backend == "fabric": - sim_utils.SimulationContext( - sim_utils.SimulationCfg(device=device, physics_manager_cfg=PhysxManagerCfg(dt=0.01, use_fabric=True)) - ) + sim_utils.SimulationContext(sim_utils.SimulationCfg(device=device, physics=PhysxCfg(dt=0.01, use_fabric=True))) return XformPrimView(pattern, device=device) diff --git a/source/isaaclab/test/terrains/check_terrain_importer.py b/source/isaaclab/test/terrains/check_terrain_importer.py index 866f07ac516..c60bf537b17 100644 --- a/source/isaaclab/test/terrains/check_terrain_importer.py +++ b/source/isaaclab/test/terrains/check_terrain_importer.py @@ -148,7 +148,7 @@ def main(): cloner.define_base_env("/World/envs") envs_prim_paths = cloner.generate_paths("/World/envs/env", num_paths=num_balls) cloner.clone(source_prim_path="/World/envs/env_0", prim_paths=envs_prim_paths, replicate_physics=True) - physics_scene_path = sim.cfg.physics_manager_cfg.physics_prim_path + physics_scene_path = sim.cfg.physics.physics_prim_path cloner.filter_collisions( physics_scene_path, "/World/collisions", prim_paths=envs_prim_paths, global_paths=["/World/ground"] ) diff --git a/source/isaaclab/test/terrains/test_terrain_importer.py b/source/isaaclab/test/terrains/test_terrain_importer.py index ab8384080ca..8c909b4dad5 100644 --- a/source/isaaclab/test/terrains/test_terrain_importer.py +++ b/source/isaaclab/test/terrains/test_terrain_importer.py @@ -318,7 +318,7 @@ def _populate_scene(sim: SimulationContext, num_balls: int = 2048, geom_sphere: prim_paths=envs_prim_paths, replicate_physics=True, ) - physics_scene_path = sim.cfg.physics_manager_cfg.physics_prim_path + physics_scene_path = sim.cfg.physics.physics_prim_path cloner.filter_collisions( physics_scene_path, "/World/collisions", prim_paths=envs_prim_paths, global_paths=["/World/ground"] ) diff --git a/source/isaaclab/test/visualization/check_scene_xr_visualization.py b/source/isaaclab/test/visualization/check_scene_xr_visualization.py index f67ebff0cb0..ed5c4ca42ed 100644 --- a/source/isaaclab/test/visualization/check_scene_xr_visualization.py +++ b/source/isaaclab/test/visualization/check_scene_xr_visualization.py @@ -37,7 +37,7 @@ import time from typing import Any -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg from pxr import Gf @@ -243,7 +243,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.005)) + sim_cfg = sim_utils.SimulationCfg(physics=PhysxCfg(dt=0.005)) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=(8, 0, 4), target=(0.0, 0.0, 0.0)) diff --git a/source/isaaclab_contrib/test/sensors/test_visuotactile_sensor.py b/source/isaaclab_contrib/test/sensors/test_visuotactile_sensor.py index 5efdb2627d9..c79d2c0e412 100644 --- a/source/isaaclab_contrib/test/sensors/test_visuotactile_sensor.py +++ b/source/isaaclab_contrib/test/sensors/test_visuotactile_sensor.py @@ -19,7 +19,7 @@ import pytest import torch -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import omni.replicator.core as rep @@ -125,7 +125,7 @@ def setup(sensor_type: str = "cube"): dt = 0.01 # Load kit helper - sim_cfg = sim_utils.SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=dt)) + sim_cfg = sim_utils.SimulationCfg(physics=PhysxCfg(dt=dt)) sim = sim_utils.SimulationContext(sim_cfg) # Ground-plane diff --git a/source/isaaclab_physx/isaaclab_physx/physics/__init__.py b/source/isaaclab_physx/isaaclab_physx/physics/__init__.py index 0f4c342f156..cc84bb7e38a 100644 --- a/source/isaaclab_physx/isaaclab_physx/physics/__init__.py +++ b/source/isaaclab_physx/isaaclab_physx/physics/__init__.py @@ -6,11 +6,11 @@ """Implementation backends for simulation interfaces.""" from .physx_manager import PhysxManager, IsaacEvents -from .physx_manager_cfg import PhysxManagerCfg +from .physx_manager_cfg import PhysxCfg __all__ = [ "PhysxManager", "IsaacEvents", - "PhysxManagerCfg", + "PhysxCfg", ] diff --git a/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py b/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py index 9c51eae2904..e5d326e8a4a 100644 --- a/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py +++ b/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py @@ -36,7 +36,7 @@ if TYPE_CHECKING: from isaaclab.sim.simulation_context import SimulationContext - from .physx_manager_cfg import PhysxManagerCfg + from .physx_cfg import PhysxCfg __all__ = ["IsaacEvents", "PhysxManager"] @@ -157,7 +157,7 @@ class PhysxManager(PhysicsManager): Lifecycle: initialize() -> reset() -> step() (repeated) -> close() """ - _cfg: ClassVar[PhysxManagerCfg | None] = None + _cfg: ClassVar[PhysxCfg | None] = None _timeline: ClassVar[omni.timeline.ITimeline] = omni.timeline.get_timeline_interface() _event_bus: ClassVar[carb.eventdispatcher.IEventDispatcher] = carb.eventdispatcher.get_eventdispatcher() diff --git a/source/isaaclab_physx/isaaclab_physx/physics/physx_manager_cfg.py b/source/isaaclab_physx/isaaclab_physx/physics/physx_manager_cfg.py index 03507f82d8b..bdb4f7cb27f 100644 --- a/source/isaaclab_physx/isaaclab_physx/physics/physx_manager_cfg.py +++ b/source/isaaclab_physx/isaaclab_physx/physics/physx_manager_cfg.py @@ -9,7 +9,7 @@ from typing import TYPE_CHECKING, Literal -from isaaclab.physics import PhysicsManagerCfg +from isaaclab.physics import PhysicsCfg from isaaclab.utils import configclass from .physx_manager import PhysxManager @@ -19,7 +19,7 @@ @configclass -class PhysxManagerCfg(PhysicsManagerCfg): +class PhysxCfg(PhysicsCfg): """Configuration for PhysX physics manager. This configuration includes all PhysX-specific settings including solver diff --git a/source/isaaclab_physx/test/sensors/check_contact_sensor.py b/source/isaaclab_physx/test/sensors/check_contact_sensor.py index 69141d2215a..8ddbfa88964 100644 --- a/source/isaaclab_physx/test/sensors/check_contact_sensor.py +++ b/source/isaaclab_physx/test/sensors/check_contact_sensor.py @@ -35,7 +35,7 @@ """Rest everything follows.""" import torch -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg from isaacsim.core.cloner import GridCloner @@ -75,7 +75,7 @@ def main(): """Spawns the ANYmal robot and clones it using Isaac Sim Cloner API.""" # Load kit helper - sim = SimulationContext(SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.005))) + sim = SimulationContext(SimulationCfg(physics=PhysxCfg(dt=0.005))) # Set main camera sim.set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0]) diff --git a/source/isaaclab_physx/test/sensors/test_contact_sensor.py b/source/isaaclab_physx/test/sensors/test_contact_sensor.py index 1a3e5210a56..cf8c1c25637 100644 --- a/source/isaaclab_physx/test/sensors/test_contact_sensor.py +++ b/source/isaaclab_physx/test/sensors/test_contact_sensor.py @@ -20,7 +20,7 @@ import pytest import torch from flaky import flaky -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import carb from pxr import PhysxSchema @@ -453,7 +453,7 @@ def test_friction_reporting(setup_simulation, grav_dir): sim_dt, _, _, _, carb_settings_iface = setup_simulation carb_settings_iface.set_bool("/physics/disableContactProcessing", True) device = "cuda:0" - sim_cfg = SimulationCfg(device=device, physics_manager_cfg=PhysxManagerCfg(dt=sim_dt, gravity=grav_dir)) + sim_cfg = SimulationCfg(device=device, physics=PhysxCfg(dt=sim_dt, gravity=grav_dir)) with build_simulation_context(sim_cfg=sim_cfg, add_lighting=False) as sim: sim._app_control_on_stop_handle = None @@ -506,7 +506,7 @@ def test_invalid_prim_paths_config(setup_simulation): sim_dt, _, _, _, carb_settings_iface = setup_simulation carb_settings_iface.set_bool("/physics/disableContactProcessing", True) device = "cuda:0" - sim_cfg = SimulationCfg(device=device, physics_manager_cfg=PhysxManagerCfg(dt=sim_dt)) + sim_cfg = SimulationCfg(device=device, physics=PhysxCfg(dt=sim_dt)) with build_simulation_context(sim_cfg=sim_cfg, add_lighting=False) as sim: sim._app_control_on_stop_handle = None @@ -540,7 +540,7 @@ def test_invalid_max_contact_points_config(setup_simulation): sim_dt, _, _, _, carb_settings_iface = setup_simulation carb_settings_iface.set_bool("/physics/disableContactProcessing", True) device = "cuda:0" - sim_cfg = SimulationCfg(device=device, physics_manager_cfg=PhysxManagerCfg(dt=sim_dt)) + sim_cfg = SimulationCfg(device=device, physics=PhysxCfg(dt=sim_dt)) with build_simulation_context(sim_cfg=sim_cfg, add_lighting=False) as sim: sim._app_control_on_stop_handle = None diff --git a/source/isaaclab_physx/test/sensors/test_frame_transformer.py b/source/isaaclab_physx/test/sensors/test_frame_transformer.py index 5509d25ec32..8d80426664f 100644 --- a/source/isaaclab_physx/test/sensors/test_frame_transformer.py +++ b/source/isaaclab_physx/test/sensors/test_frame_transformer.py @@ -17,7 +17,7 @@ import pytest import scipy.spatial.transform as tf import torch -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils import isaaclab.utils.math as math_utils @@ -75,7 +75,7 @@ class MySceneCfg(InteractiveSceneCfg): @pytest.fixture def sim(): """Create a simulation context.""" - sim_cfg = sim_utils.SimulationCfg(device="cpu", physics_manager_cfg=PhysxManagerCfg(dt=0.005)) + sim_cfg = sim_utils.SimulationCfg(device="cpu", physics=PhysxCfg(dt=0.005)) with sim_utils.build_simulation_context(sim_cfg=sim_cfg) as sim: sim._app_control_on_stop_handle = None # Set main camera diff --git a/source/isaaclab_physx/test/sensors/test_imu.py b/source/isaaclab_physx/test/sensors/test_imu.py index da5ed4e2503..2be9ced8a4d 100644 --- a/source/isaaclab_physx/test/sensors/test_imu.py +++ b/source/isaaclab_physx/test/sensors/test_imu.py @@ -17,7 +17,7 @@ import pytest import torch -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils import isaaclab.utils.math as math_utils @@ -203,7 +203,7 @@ def __post_init__(self): def setup_sim(): """Create a simulation context and scene.""" sim_cfg = sim_utils.SimulationCfg( - physics_manager_cfg=PhysxManagerCfg(dt=0.001, solver_type=0) + physics=PhysxCfg(dt=0.001, solver_type=0) ) # 0: PGS, 1: TGS --> use PGS for more accurate results with sim_utils.build_simulation_context(sim_cfg=sim_cfg) as sim: sim._app_control_on_stop_handle = None diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/allegro_hand/allegro_hand_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/direct/allegro_hand/allegro_hand_env_cfg.py index 12e75257f39..6007d03ba48 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/allegro_hand/allegro_hand_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/allegro_hand/allegro_hand_env_cfg.py @@ -4,7 +4,7 @@ # SPDX-License-Identifier: BSD-3-Clause -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import ArticulationCfg, RigidObjectCfg @@ -32,7 +32,7 @@ class AllegroHandEnvCfg(DirectRLEnvCfg): # simulation sim: SimulationCfg = SimulationCfg( render_interval=decimation, - physics_manager_cfg=PhysxManagerCfg( + physics=PhysxCfg( dt=1 / 120, physics_material=RigidBodyMaterialCfg( static_friction=1.0, diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/ant/ant_env.py b/source/isaaclab_tasks/isaaclab_tasks/direct/ant/ant_env.py index 53fa474502a..dd3f9ff5dae 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/ant/ant_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/ant/ant_env.py @@ -5,7 +5,7 @@ from __future__ import annotations -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import ArticulationCfg @@ -31,7 +31,7 @@ class AntEnvCfg(DirectRLEnvCfg): state_space = 0 # simulation - sim: SimulationCfg = SimulationCfg(render_interval=decimation, physics_manager_cfg=PhysxManagerCfg(dt=1 / 120)) + sim: SimulationCfg = SimulationCfg(render_interval=decimation, physics=PhysxCfg(dt=1 / 120)) terrain = TerrainImporterCfg( prim_path="/World/ground", terrain_type="plane", diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/anymal_c/anymal_c_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/direct/anymal_c/anymal_c_env_cfg.py index 089b87e4df7..8e581d1e0c1 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/anymal_c/anymal_c_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/anymal_c/anymal_c_env_cfg.py @@ -3,7 +3,7 @@ # # SPDX-License-Identifier: BSD-3-Clause -from isaaclab_physx.physics import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import isaaclab.envs.mdp as mdp import isaaclab.sim as sim_utils @@ -64,7 +64,7 @@ class AnymalCFlatEnvCfg(DirectRLEnvCfg): # simulation sim: SimulationCfg = SimulationCfg( render_interval=decimation, - physics_manager_cfg=PhysxManagerCfg( + physics=PhysxCfg( dt=1 / 200, physics_material=sim_utils.RigidBodyMaterialCfg( friction_combine_mode="multiply", diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/automate/assembly_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/direct/automate/assembly_env_cfg.py index 3fe4d7ddaed..ae242e033ab 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/automate/assembly_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/automate/assembly_env_cfg.py @@ -3,7 +3,7 @@ # # SPDX-License-Identifier: BSD-3-Clause -from isaaclab_physx.physics import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.actuators import ImplicitActuatorCfg @@ -107,7 +107,7 @@ class AssemblyEnvCfg(DirectRLEnvCfg): episode_length_s = 5.0 sim: SimulationCfg = SimulationCfg( device="cuda:0", - physics_manager_cfg=PhysxManagerCfg( + physics=PhysxCfg( dt=1 / 120, gravity=(0.0, 0.0, -9.81), solver_type=1, diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/automate/disassembly_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/direct/automate/disassembly_env_cfg.py index e9f0e7164e8..8d3ab83611e 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/automate/disassembly_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/automate/disassembly_env_cfg.py @@ -3,7 +3,8 @@ # # SPDX-License-Identifier: BSD-3-Clause -from isaaclab_physx.physics import PhysxManagerCfg + +from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.actuators import ImplicitActuatorCfg @@ -107,7 +108,7 @@ class DisassemblyEnvCfg(DirectRLEnvCfg): episode_length_s = 5.0 sim: SimulationCfg = SimulationCfg( device="cuda:0", - physics_manager_cfg=PhysxManagerCfg( + physics=PhysxCfg( dt=1 / 120, gravity=(0.0, 0.0, -9.81), solver_type=1, diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/cart_double_pendulum/cart_double_pendulum_env.py b/source/isaaclab_tasks/isaaclab_tasks/direct/cart_double_pendulum/cart_double_pendulum_env.py index 68ee6ac9f14..7bf08d272fa 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/cart_double_pendulum/cart_double_pendulum_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/cart_double_pendulum/cart_double_pendulum_env.py @@ -9,7 +9,7 @@ from collections.abc import Sequence import torch -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import Articulation, ArticulationCfg @@ -34,7 +34,7 @@ class CartDoublePendulumEnvCfg(DirectMARLEnvCfg): state_space = -1 # simulation - sim: SimulationCfg = SimulationCfg(render_interval=decimation, physics_manager_cfg=PhysxManagerCfg(dt=1 / 120)) + sim: SimulationCfg = SimulationCfg(render_interval=decimation, physics=PhysxCfg(dt=1 / 120)) # robot robot_cfg: ArticulationCfg = CART_DOUBLE_PENDULUM_CFG.replace(prim_path="/World/envs/env_.*/Robot") diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/cartpole/cartpole_camera_env.py b/source/isaaclab_tasks/isaaclab_tasks/direct/cartpole/cartpole_camera_env.py index 458df9ee995..19685d654d0 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/cartpole/cartpole_camera_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/cartpole/cartpole_camera_env.py @@ -9,7 +9,7 @@ from collections.abc import Sequence import torch -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import Articulation, ArticulationCfg @@ -31,7 +31,7 @@ class CartpoleRGBCameraEnvCfg(DirectRLEnvCfg): action_scale = 100.0 # [N] # simulation - sim: SimulationCfg = SimulationCfg(render_interval=decimation, physics_manager_cfg=PhysxManagerCfg(dt=1 / 120)) + sim: SimulationCfg = SimulationCfg(render_interval=decimation, physics=PhysxCfg(dt=1 / 120)) # robot robot_cfg: ArticulationCfg = CARTPOLE_CFG.replace(prim_path="/World/envs/env_.*/Robot") diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/cartpole/cartpole_env.py b/source/isaaclab_tasks/isaaclab_tasks/direct/cartpole/cartpole_env.py index b5e9db45589..e2a7dcc4773 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/cartpole/cartpole_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/cartpole/cartpole_env.py @@ -9,7 +9,7 @@ from collections.abc import Sequence import torch -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import Articulation, ArticulationCfg @@ -34,7 +34,7 @@ class CartpoleEnvCfg(DirectRLEnvCfg): state_space = 0 # simulation - sim: SimulationCfg = SimulationCfg(render_interval=decimation, physics_manager_cfg=PhysxManagerCfg(dt=1 / 120)) + sim: SimulationCfg = SimulationCfg(render_interval=decimation, physics=PhysxCfg(dt=1 / 120)) # robot robot_cfg: ArticulationCfg = CARTPOLE_CFG.replace(prim_path="/World/envs/env_.*/Robot") diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/factory/factory_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/direct/factory/factory_env_cfg.py index 0ec12ed5be8..e7d8782024e 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/factory/factory_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/factory/factory_env_cfg.py @@ -3,7 +3,7 @@ # # SPDX-License-Identifier: BSD-3-Clause -from isaaclab_physx.physics import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.actuators import ImplicitActuatorCfg @@ -98,7 +98,7 @@ class FactoryEnvCfg(DirectRLEnvCfg): episode_length_s = 10.0 # Probably need to override. sim: SimulationCfg = SimulationCfg( device="cuda:0", - physics_manager_cfg=PhysxManagerCfg( + physics=PhysxCfg( dt=1 / 120, gravity=(0.0, 0.0, -9.81), solver_type=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 cce01214517..9c9954c03fa 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 @@ -6,7 +6,7 @@ from __future__ import annotations import torch -from isaaclab_physx.physics import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg from pxr import UsdGeom @@ -35,7 +35,7 @@ class FrankaCabinetEnvCfg(DirectRLEnvCfg): # simulation sim: SimulationCfg = SimulationCfg( render_interval=decimation, - physics_manager_cfg=PhysxManagerCfg( + physics=PhysxCfg( dt=1 / 120, physics_material=sim_utils.RigidBodyMaterialCfg( friction_combine_mode="multiply", diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/humanoid/humanoid_env.py b/source/isaaclab_tasks/isaaclab_tasks/direct/humanoid/humanoid_env.py index ed5c569b00c..23f71129ca8 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/humanoid/humanoid_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/humanoid/humanoid_env.py @@ -5,7 +5,7 @@ from __future__ import annotations -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import ArticulationCfg @@ -31,7 +31,7 @@ class HumanoidEnvCfg(DirectRLEnvCfg): state_space = 0 # simulation - sim: SimulationCfg = SimulationCfg(render_interval=decimation, physics_manager_cfg=PhysxManagerCfg(dt=1 / 120)) + sim: SimulationCfg = SimulationCfg(render_interval=decimation, physics=PhysxCfg(dt=1 / 120)) terrain = TerrainImporterCfg( prim_path="/World/ground", terrain_type="plane", diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/humanoid_amp/humanoid_amp_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/direct/humanoid_amp/humanoid_amp_env_cfg.py index 4c80654c0fe..0a51d30d214 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/humanoid_amp/humanoid_amp_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/humanoid_amp/humanoid_amp_env_cfg.py @@ -8,7 +8,7 @@ import os from dataclasses import MISSING -from isaaclab_physx.physics import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg from isaaclab.actuators import ImplicitActuatorCfg from isaaclab.assets import ArticulationCfg @@ -53,7 +53,7 @@ class HumanoidAmpEnvCfg(DirectRLEnvCfg): # simulation sim: SimulationCfg = SimulationCfg( render_interval=decimation, - physics_manager_cfg=PhysxManagerCfg( + physics=PhysxCfg( dt=1 / 60, gpu_found_lost_pairs_capacity=2**23, gpu_total_aggregate_pairs_capacity=2**23, diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/quadcopter/quadcopter_env.py b/source/isaaclab_tasks/isaaclab_tasks/direct/quadcopter/quadcopter_env.py index 8f536b1b04f..b23ea0811e0 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/quadcopter/quadcopter_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/quadcopter/quadcopter_env.py @@ -7,7 +7,7 @@ import gymnasium as gym import torch -from isaaclab_physx.physics import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import Articulation, ArticulationCfg @@ -62,7 +62,7 @@ class QuadcopterEnvCfg(DirectRLEnvCfg): # simulation sim: SimulationCfg = SimulationCfg( render_interval=decimation, - physics_manager_cfg=PhysxManagerCfg( + physics=PhysxCfg( dt=1 / 100, physics_material=sim_utils.RigidBodyMaterialCfg( friction_combine_mode="multiply", diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/shadow_hand/shadow_hand_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/direct/shadow_hand/shadow_hand_env_cfg.py index 48328217dbc..220f67b66db 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/shadow_hand/shadow_hand_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/shadow_hand/shadow_hand_env_cfg.py @@ -3,8 +3,7 @@ # # SPDX-License-Identifier: BSD-3-Clause - -from isaaclab_physx.physics import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import isaaclab.envs.mdp as mdp import isaaclab.sim as sim_utils @@ -130,7 +129,7 @@ class ShadowHandEnvCfg(DirectRLEnvCfg): # simulation sim: SimulationCfg = SimulationCfg( render_interval=decimation, - physics_manager_cfg=PhysxManagerCfg( + physics=PhysxCfg( dt=1 / 120, physics_material=RigidBodyMaterialCfg( static_friction=1.0, @@ -245,7 +244,7 @@ class ShadowHandOpenAIEnvCfg(ShadowHandEnvCfg): # simulation sim: SimulationCfg = SimulationCfg( render_interval=decimation, - physics_manager_cfg=PhysxManagerCfg( + physics=PhysxCfg( dt=1 / 60, physics_material=RigidBodyMaterialCfg( static_friction=1.0, diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/shadow_hand_over/shadow_hand_over_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/direct/shadow_hand_over/shadow_hand_over_env_cfg.py index 35069c75af7..b7e55671715 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/shadow_hand_over/shadow_hand_over_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/shadow_hand_over/shadow_hand_over_env_cfg.py @@ -3,8 +3,7 @@ # # SPDX-License-Identifier: BSD-3-Clause - -from isaaclab_physx.physics import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import isaaclab.envs.mdp as mdp import isaaclab.sim as sim_utils @@ -127,7 +126,7 @@ class ShadowHandOverEnvCfg(DirectMARLEnvCfg): # simulation sim: SimulationCfg = SimulationCfg( render_interval=decimation, - physics_manager_cfg=PhysxManagerCfg( + physics=PhysxCfg( dt=1 / 120, physics_material=RigidBodyMaterialCfg( static_friction=1.0, diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/classic/ant/ant_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/classic/ant/ant_env_cfg.py index 0b3980b2815..d10f600a804 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/classic/ant/ant_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/classic/ant/ant_env_cfg.py @@ -175,9 +175,9 @@ def __post_init__(self): self.decimation = 2 self.episode_length_s = 16.0 # simulation settings - self.sim.physics_manager_cfg.dt = 1 / 120.0 + self.sim.physics.dt = 1 / 120.0 self.sim.render_interval = self.decimation - self.sim.physics_manager_cfg.bounce_threshold_velocity = 0.2 + self.sim.physics.bounce_threshold_velocity = 0.2 # default friction material self.sim.physics_material.static_friction = 1.0 self.sim.physics_material.dynamic_friction = 1.0 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/classic/cartpole/cartpole_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/classic/cartpole/cartpole_env_cfg.py index 1e72a7d6056..c5d486de0a7 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/classic/cartpole/cartpole_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/classic/cartpole/cartpole_env_cfg.py @@ -177,5 +177,5 @@ def __post_init__(self) -> None: # viewer settings self.viewer.eye = (8.0, 0.0, 5.0) # simulation settings - self.sim.physics_manager_cfg.dt = 1 / 120 + self.sim.physics.dt = 1 / 120 self.sim.render_interval = self.decimation diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/classic/humanoid/humanoid_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/classic/humanoid/humanoid_env_cfg.py index 474f5449735..5995b425702 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/classic/humanoid/humanoid_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/classic/humanoid/humanoid_env_cfg.py @@ -212,9 +212,9 @@ def __post_init__(self): self.decimation = 2 self.episode_length_s = 16.0 # simulation settings - self.sim.physics_manager_cfg.dt = 1 / 120.0 + self.sim.physics.dt = 1 / 120.0 self.sim.render_interval = self.decimation - self.sim.physics_manager_cfg.bounce_threshold_velocity = 0.2 + self.sim.physics.bounce_threshold_velocity = 0.2 # default friction material self.sim.physics_material.static_friction = 1.0 self.sim.physics_material.dynamic_friction = 1.0 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/track_position_state_based/config/arl_robot_1/no_obstacle_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/track_position_state_based/config/arl_robot_1/no_obstacle_env_cfg.py index 59efc3b4ee4..c4403c9565e 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/track_position_state_based/config/arl_robot_1/no_obstacle_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/track_position_state_based/config/arl_robot_1/no_obstacle_env_cfg.py @@ -21,7 +21,7 @@ def __post_init__(self): super().__post_init__() # switch robot to arl_robot_1 self.scene.robot = ARL_ROBOT_1_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot") - self.scene.robot.actuators["thrusters"].dt = self.sim.physics_manager_cfg.dt + self.scene.robot.actuators["thrusters"].dt = self.sim.physics.dt @configclass diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/track_position_state_based/config/arl_robot_1/track_position_state_based_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/track_position_state_based/config/arl_robot_1/track_position_state_based_env_cfg.py index bab017bb340..b07795abeca 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/track_position_state_based/config/arl_robot_1/track_position_state_based_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/track_position_state_based/config/arl_robot_1/track_position_state_based_env_cfg.py @@ -218,12 +218,12 @@ def __post_init__(self): self.decimation = 10 self.episode_length_s = 5.0 # simulation settings - self.sim.physics_manager_cfg.dt = 0.01 + self.sim.physics.dt = 0.01 self.sim.render_interval = self.decimation - self.sim.physics_manager_cfg.physics_material = sim_utils.RigidBodyMaterialCfg( + self.sim.physics.physics_material = sim_utils.RigidBodyMaterialCfg( friction_combine_mode="multiply", restitution_combine_mode="multiply", static_friction=1.0, dynamic_friction=1.0, ) - self.sim.physics_manager_cfg.gpu_max_rigid_patch_count = 10 * 2**15 + self.sim.physics.gpu_max_rigid_patch_count = 10 * 2**15 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomanipulation/pick_place/fixed_base_upper_body_ik_g1_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomanipulation/pick_place/fixed_base_upper_body_ik_g1_env_cfg.py index bfdb04a77b6..e235d1be63f 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomanipulation/pick_place/fixed_base_upper_body_ik_g1_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomanipulation/pick_place/fixed_base_upper_body_ik_g1_env_cfg.py @@ -187,7 +187,7 @@ def __post_init__(self): self.decimation = 4 self.episode_length_s = 20.0 # simulation settings - self.sim.physics_manager_cfg.dt = 1 / 200 # 200Hz + self.sim.physics.dt = 1 / 200 # 200Hz self.sim.render_interval = 2 # Set the URDF and mesh paths for the IK controller diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomanipulation/pick_place/locomanipulation_g1_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomanipulation/pick_place/locomanipulation_g1_env_cfg.py index a839e53fce9..5626ea8d8da 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomanipulation/pick_place/locomanipulation_g1_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomanipulation/pick_place/locomanipulation_g1_env_cfg.py @@ -204,7 +204,7 @@ def __post_init__(self): self.decimation = 4 self.episode_length_s = 20.0 # simulation settings - self.sim.physics_manager_cfg.dt = 1 / 200 # 200Hz + self.sim.physics.dt = 1 / 200 # 200Hz self.sim.render_interval = 2 # Set the URDF and mesh paths for the IK controller diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/digit/rough_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/digit/rough_env_cfg.py index 9d296a1532c..81b64be322c 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/digit/rough_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/digit/rough_env_cfg.py @@ -218,14 +218,14 @@ class DigitRoughEnvCfg(LocomotionVelocityRoughEnvCfg): def __post_init__(self): super().__post_init__() self.decimation = 4 - self.sim.physics_manager_cfg.dt = 0.005 + self.sim.physics.dt = 0.005 # Scene self.scene.robot = DIGIT_V4_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot") self.scene.height_scanner.prim_path = "{ENV_REGEX_NS}/Robot/torso_base" self.scene.contact_forces.history_length = self.decimation - self.scene.contact_forces.update_period = self.sim.physics_manager_cfg.dt - self.scene.height_scanner.update_period = self.decimation * self.sim.physics_manager_cfg.dt + self.scene.contact_forces.update_period = self.sim.physics.dt + self.scene.height_scanner.update_period = self.decimation * self.sim.physics.dt # Events: self.events.add_base_mass.params["asset_cfg"] = SceneEntityCfg("robot", body_names="torso_base") diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/spot/flat_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/spot/flat_env_cfg.py index 1799d3cec02..8b183f38398 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/spot/flat_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/spot/flat_env_cfg.py @@ -318,15 +318,15 @@ def __post_init__(self): self.decimation = 10 # 50 Hz self.episode_length_s = 20.0 # simulation settings - self.sim.physics_manager_cfg.dt = 0.002 # 500 Hz + self.sim.physics.dt = 0.002 # 500 Hz self.sim.render_interval = self.decimation - self.sim.physics_manager_cfg.physics_material.static_friction = 1.0 - self.sim.physics_manager_cfg.physics_material.dynamic_friction = 1.0 - self.sim.physics_manager_cfg.physics_material.friction_combine_mode = "multiply" - self.sim.physics_manager_cfg.physics_material.restitution_combine_mode = "multiply" + self.sim.physics.physics_material.static_friction = 1.0 + self.sim.physics.physics_material.dynamic_friction = 1.0 + self.sim.physics.physics_material.friction_combine_mode = "multiply" + self.sim.physics.physics_material.restitution_combine_mode = "multiply" # update sensor update periods # we tick all the sensors based on the smallest update period (physics update period) - self.scene.contact_forces.update_period = self.sim.physics_manager_cfg.dt + self.scene.contact_forces.update_period = self.sim.physics.dt # switch robot to Spot-d self.scene.robot = SPOT_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot") diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/velocity_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/velocity_env_cfg.py index ac4043a0dae..9920ed7b3b0 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/velocity_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/velocity_env_cfg.py @@ -308,16 +308,16 @@ def __post_init__(self): self.decimation = 4 self.episode_length_s = 20.0 # simulation settings - self.sim.physics_manager_cfg.dt = 0.005 + self.sim.physics.dt = 0.005 self.sim.render_interval = self.decimation - self.sim.physics_manager_cfg.physics_material = self.scene.terrain.physics_material - self.sim.physics_manager_cfg.gpu_max_rigid_patch_count = 10 * 2**15 + self.sim.physics.physics_material = self.scene.terrain.physics_material + self.sim.physics.gpu_max_rigid_patch_count = 10 * 2**15 # update sensor update periods # we tick all the sensors based on the smallest update period (physics update period) if self.scene.height_scanner is not None: - self.scene.height_scanner.update_period = self.decimation * self.sim.physics_manager_cfg.dt + self.scene.height_scanner.update_period = self.decimation * self.sim.physics.dt if self.scene.contact_forces is not None: - self.scene.contact_forces.update_period = self.sim.physics_manager_cfg.dt + self.scene.contact_forces.update_period = self.sim.physics.dt # check if terrain levels curriculum is enabled - if so, enable curriculum for terrain generator # this generates terrains with increasing difficulty and is useful for training diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/cabinet_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/cabinet_env_cfg.py index b40aba8d36a..d231be8bcfb 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/cabinet_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/cabinet_env_cfg.py @@ -271,7 +271,7 @@ def __post_init__(self): self.viewer.eye = (-2.0, 2.0, 2.0) self.viewer.lookat = (0.8, 0.0, 0.5) # simulation settings - self.sim.physics_manager_cfg.dt = 1 / 60 # 60Hz + self.sim.physics.dt = 1 / 60 # 60Hz self.sim.render_interval = self.decimation - self.sim.physics_manager_cfg.bounce_threshold_velocity = 0.01 - self.sim.physics_manager_cfg.friction_correlation_distance = 0.00625 + self.sim.physics.bounce_threshold_velocity = 0.01 + self.sim.physics.friction_correlation_distance = 0.00625 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/cabinet_openarm_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/cabinet_openarm_env_cfg.py index 3841f242b4a..942cadfb3a5 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/cabinet_openarm_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/cabinet_openarm_env_cfg.py @@ -276,7 +276,7 @@ def __post_init__(self): self.viewer.eye = (-2.0, 2.0, 2.0) self.viewer.lookat = (0.8, 0.0, 0.5) # simulation settings - self.sim.physics_manager_cfg.dt = 1 / 60 # 60Hz + self.sim.physics.dt = 1 / 60 # 60Hz self.sim.render_interval = self.decimation - self.sim.physics_manager_cfg.bounce_threshold_velocity = 0.01 - self.sim.physics_manager_cfg.friction_correlation_distance = 0.00625 + self.sim.physics.bounce_threshold_velocity = 0.01 + self.sim.physics.friction_correlation_distance = 0.00625 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/deploy/gear_assembly/gear_assembly_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/deploy/gear_assembly/gear_assembly_env_cfg.py index 5f4c00781ed..5755c154bca 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/deploy/gear_assembly/gear_assembly_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/deploy/gear_assembly/gear_assembly_env_cfg.py @@ -6,7 +6,7 @@ import os from dataclasses import MISSING -from isaaclab_physx.physics import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import ArticulationCfg, AssetBaseCfg, RigidObjectCfg @@ -303,7 +303,7 @@ class GearAssemblyEnvCfg(ManagerBasedRLEnvCfg): terminations: TerminationsCfg = TerminationsCfg() events: EventCfg = EventCfg() sim: SimulationCfg = SimulationCfg( - physics_manager_cfg=PhysxManagerCfg( + physics=PhysxCfg( # Important to prevent collisionStackSize buffer overflow in contact-rich environments. gpu_collision_stack_size=2**30, gpu_max_rigid_contact_count=2**23, @@ -319,7 +319,7 @@ def __post_init__(self): # simulation settings self.decimation = 4 self.sim.render_interval = self.decimation - self.sim.physics_manager_cfg.dt = 1.0 / 120.0 + self.sim.physics.dt = 1.0 / 120.0 self.gear_offsets = { "gear_small": [0.076125, 0.0, 0.0], diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/deploy/reach/reach_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/deploy/reach/reach_env_cfg.py index ec7e7baab92..e48e27152f2 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/deploy/reach/reach_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/deploy/reach/reach_env_cfg.py @@ -212,4 +212,4 @@ def __post_init__(self): self.episode_length_s = 12.0 self.viewer.eye = (3.5, 3.5, 3.5) # simulation settings - self.sim.physics_manager_cfg.dt = 1.0 / 120.0 + self.sim.physics.dt = 1.0 / 120.0 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/dexsuite/dexsuite_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/dexsuite/dexsuite_env_cfg.py index c1d9a76b8f7..daab70f8e26 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/dexsuite/dexsuite_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/dexsuite/dexsuite_env_cfg.py @@ -423,10 +423,10 @@ def __post_init__(self): self.is_finite_horizon = True # simulation settings - self.sim.physics_manager_cfg.dt = 1 / 120 + self.sim.dt = 1 / 120 self.sim.render_interval = self.decimation - self.sim.physics_manager_cfg.bounce_threshold_velocity = 0.01 - self.sim.physics_manager_cfg.gpu_max_rigid_patch_count = 4 * 5 * 2**15 + self.sim.physx.bounce_threshold_velocity = 0.01 + self.sim.physx.gpu_max_rigid_patch_count = 4 * 5 * 2**15 if self.curriculum is not None: self.curriculum.adr.params["pos_tol"] = self.rewards.success.params["pos_std"] / 2 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/inhand/inhand_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/inhand/inhand_env_cfg.py index ee20a0dc28f..f8246fa8fd5 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/inhand/inhand_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/inhand/inhand_env_cfg.py @@ -7,7 +7,7 @@ from dataclasses import MISSING -from isaaclab_physx.physics import PhysxManagerCfg +from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import ArticulationCfg, AssetBaseCfg, RigidObjectCfg @@ -317,7 +317,7 @@ class InHandObjectEnvCfg(ManagerBasedRLEnvCfg): scene: InHandObjectSceneCfg = InHandObjectSceneCfg(num_envs=8192, env_spacing=0.6) # Simulation settings sim: SimulationCfg = SimulationCfg( - physics_manager_cfg=PhysxManagerCfg( + physics=PhysxCfg( physics_material=RigidBodyMaterialCfg( static_friction=1.0, dynamic_friction=1.0, @@ -342,7 +342,7 @@ def __post_init__(self): self.decimation = 4 self.episode_length_s = 20.0 # simulation settings - self.sim.physics_manager_cfg.dt = 1.0 / 120.0 + self.sim.physics.dt = 1.0 / 120.0 self.sim.render_interval = self.decimation # change viewer settings self.viewer.eye = (2.0, 2.0, 2.0) diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/lift_openarm_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/lift_openarm_env_cfg.py index 46739d3de79..b8a44b3bd71 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/lift_openarm_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/lift_openarm_env_cfg.py @@ -233,10 +233,10 @@ def __post_init__(self): self.decimation = 2 self.episode_length_s = 5.0 # simulation settings - self.sim.physics_manager_cfg.dt = 0.01 # 100Hz + self.sim.physics.dt = 0.01 # 100Hz self.sim.render_interval = self.decimation - self.sim.physics_manager_cfg.bounce_threshold_velocity = 0.01 - self.sim.physics_manager_cfg.gpu_found_lost_aggregate_pairs_capacity = 1024 * 1024 * 4 - self.sim.physics_manager_cfg.gpu_total_aggregate_pairs_capacity = 16 * 1024 - self.sim.physics_manager_cfg.friction_correlation_distance = 0.00625 + self.sim.physics.bounce_threshold_velocity = 0.01 + self.sim.physics.gpu_found_lost_aggregate_pairs_capacity = 1024 * 1024 * 4 + self.sim.physics.gpu_total_aggregate_pairs_capacity = 16 * 1024 + self.sim.physics.friction_correlation_distance = 0.00625 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/lift_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/lift_env_cfg.py index 2d93ca88ce9..1207e0d3aaa 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/lift_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/lift_env_cfg.py @@ -214,10 +214,10 @@ def __post_init__(self): self.decimation = 2 self.episode_length_s = 5.0 # simulation settings - self.sim.physics_manager_cfg.dt = 0.01 # 100Hz + self.sim.physics.dt = 0.01 # 100Hz self.sim.render_interval = self.decimation - self.sim.physics_manager_cfg.bounce_threshold_velocity = 0.01 - self.sim.physics_manager_cfg.gpu_found_lost_aggregate_pairs_capacity = 1024 * 1024 * 4 - self.sim.physics_manager_cfg.gpu_total_aggregate_pairs_capacity = 16 * 1024 - self.sim.physics_manager_cfg.friction_correlation_distance = 0.00625 + self.sim.physics.bounce_threshold_velocity = 0.01 + self.sim.physics.gpu_found_lost_aggregate_pairs_capacity = 1024 * 1024 * 4 + self.sim.physics.gpu_total_aggregate_pairs_capacity = 16 * 1024 + self.sim.physics.friction_correlation_distance = 0.00625 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/exhaustpipe_gr1t2_base_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/exhaustpipe_gr1t2_base_env_cfg.py index cf3e97fb1f2..6eeef3c4d75 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/exhaustpipe_gr1t2_base_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/exhaustpipe_gr1t2_base_env_cfg.py @@ -325,7 +325,7 @@ def __post_init__(self): self.decimation = 5 self.episode_length_s = 20.0 # simulation settings - self.sim.physics_manager_cfg.dt = 1 / 100 + self.sim.physics.dt = 1 / 100 self.sim.render_interval = 2 # Set settings for camera rendering diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/nutpour_gr1t2_base_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/nutpour_gr1t2_base_env_cfg.py index 6709f0a2355..044bc28cad3 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/nutpour_gr1t2_base_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/nutpour_gr1t2_base_env_cfg.py @@ -360,7 +360,7 @@ def __post_init__(self): self.decimation = 5 self.episode_length_s = 20.0 # simulation settings - self.sim.physics_manager_cfg.dt = 1 / 100 + self.sim.physics.dt = 1 / 100 self.sim.render_interval = 2 # Set settings for camera rendering diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/pickplace_gr1t2_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/pickplace_gr1t2_env_cfg.py index 26420595270..b199b93b25c 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/pickplace_gr1t2_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/pickplace_gr1t2_env_cfg.py @@ -377,7 +377,7 @@ def __post_init__(self): self.decimation = 6 self.episode_length_s = 20.0 # simulation settings - self.sim.physics_manager_cfg.dt = 1 / 120 # 120Hz + self.sim.physics.dt = 1 / 120 # 120Hz self.sim.render_interval = 2 # Convert USD to URDF and change revolute joints to fixed diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/pickplace_gr1t2_waist_enabled_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/pickplace_gr1t2_waist_enabled_env_cfg.py index 6c90d6baf4a..37f382bb673 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/pickplace_gr1t2_waist_enabled_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/pickplace_gr1t2_waist_enabled_env_cfg.py @@ -51,7 +51,7 @@ def __post_init__(self): self.decimation = 6 self.episode_length_s = 20.0 # simulation settings - self.sim.physics_manager_cfg.dt = 1 / 120 # 120Hz + self.sim.physics.dt = 1 / 120 # 120Hz self.sim.render_interval = 2 # Add waist joint to pink_ik_cfg diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/pickplace_unitree_g1_inspire_hand_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/pickplace_unitree_g1_inspire_hand_env_cfg.py index 2d5de66e429..b67b0a00d9b 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/pickplace_unitree_g1_inspire_hand_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/pickplace_unitree_g1_inspire_hand_env_cfg.py @@ -368,7 +368,7 @@ def __post_init__(self): self.decimation = 6 self.episode_length_s = 20.0 # simulation settings - self.sim.physics_manager_cfg.dt = 1 / 120 # 120Hz + self.sim.physics.dt = 1 / 120 # 120Hz self.sim.render_interval = 2 # Convert USD to URDF and change revolute joints to fixed diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/place/config/agibot/place_toy2box_rmp_rel_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/place/config/agibot/place_toy2box_rmp_rel_env_cfg.py index 16b7657c850..25709496f23 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/place/config/agibot/place_toy2box_rmp_rel_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/place/config/agibot/place_toy2box_rmp_rel_env_cfg.py @@ -192,10 +192,10 @@ def __post_init__(self): self.sim.render_interval = self.decimation - self.sim.physics_manager_cfg.bounce_threshold_velocity = 0.01 - self.sim.physics_manager_cfg.gpu_found_lost_aggregate_pairs_capacity = 1024 * 1024 * 4 - self.sim.physics_manager_cfg.gpu_total_aggregate_pairs_capacity = 16 * 1024 - self.sim.physics_manager_cfg.friction_correlation_distance = 0.00625 + self.sim.physics.bounce_threshold_velocity = 0.01 + self.sim.physics.gpu_found_lost_aggregate_pairs_capacity = 1024 * 1024 * 4 + self.sim.physics.gpu_total_aggregate_pairs_capacity = 16 * 1024 + self.sim.physics.friction_correlation_distance = 0.00625 # set viewer to see the whole scene self.viewer.eye = [1.5, -1.0, 1.5] @@ -339,7 +339,7 @@ def __post_init__(self): ) # Set the simulation parameters - self.sim.physics_manager_cfg.dt = 1 / 60 + self.sim.physics.dt = 1 / 60 self.sim.render_interval = 6 self.decimation = 3 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/place/config/agibot/place_upright_mug_rmp_rel_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/place/config/agibot/place_upright_mug_rmp_rel_env_cfg.py index e0124a58af6..acf35eafa13 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/place/config/agibot/place_upright_mug_rmp_rel_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/place/config/agibot/place_upright_mug_rmp_rel_env_cfg.py @@ -276,7 +276,7 @@ def __post_init__(self): ) # Set the simulation parameters - self.sim.physics_manager_cfg.dt = 1 / 60 + self.sim.physics.dt = 1 / 60 self.sim.render_interval = 6 self.decimation = 3 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/reach_openarm_bi_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/reach_openarm_bi_env_cfg.py index 1a00aa98e56..656a6e9e744 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/reach_openarm_bi_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/reach_openarm_bi_env_cfg.py @@ -332,4 +332,4 @@ def __post_init__(self): self.episode_length_s = 24.0 self.viewer.eye = (3.5, 3.5, 3.5) # simulation settings - self.sim.physics_manager_cfg.dt = 1.0 / 60.0 + self.sim.physics.dt = 1.0 / 60.0 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/reach_openarm_uni_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/reach_openarm_uni_env_cfg.py index 2a533a30795..c126cf3434b 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/reach_openarm_uni_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/reach_openarm_uni_env_cfg.py @@ -245,4 +245,4 @@ def __post_init__(self): self.episode_length_s = 12.0 self.viewer.eye = (3.5, 3.5, 3.5) # simulation settings - self.sim.physics_manager_cfg.dt = 1.0 / 60.0 + self.sim.physics.dt = 1.0 / 60.0 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/reach_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/reach_env_cfg.py index b7cae39d9c6..e53cc4ca928 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/reach_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/reach_env_cfg.py @@ -209,7 +209,7 @@ def __post_init__(self): self.episode_length_s = 12.0 self.viewer.eye = (3.5, 3.5, 3.5) # simulation settings - self.sim.physics_manager_cfg.dt = 1.0 / 60.0 + self.sim.physics.dt = 1.0 / 60.0 self.teleop_devices = DevicesCfg( devices={ diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/config/galbot/stack_rmp_rel_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/config/galbot/stack_rmp_rel_env_cfg.py index e9511fc8024..809fca4e50c 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/config/galbot/stack_rmp_rel_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/config/galbot/stack_rmp_rel_env_cfg.py @@ -60,7 +60,7 @@ def __post_init__(self): ) # Set the simulation parameters - self.sim.physics_manager_cfg.dt = 1 / 60 + self.sim.physics.dt = 1 / 60 self.sim.render_interval = 6 self.decimation = 3 @@ -126,14 +126,14 @@ def __post_init__(self): use_relative_mode=self.use_relative_mode, ) # Set the simulation parameters - self.sim.physics_manager_cfg.dt = 1 / 120 + self.sim.physics.dt = 1 / 120 self.sim.render_interval = 6 self.decimation = 6 self.episode_length_s = 30.0 # Enable CCD to avoid tunneling - self.sim.physics_manager_cfg.enable_ccd = True + self.sim.physics.enable_ccd = True self.teleop_devices = DevicesCfg( devices={ diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/config/ur10_gripper/stack_joint_pos_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/config/ur10_gripper/stack_joint_pos_env_cfg.py index 277056daa86..718b95fc167 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/config/ur10_gripper/stack_joint_pos_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/config/ur10_gripper/stack_joint_pos_env_cfg.py @@ -132,7 +132,7 @@ def __post_init__(self): self.decimation = 5 self.episode_length_s = 30.0 # simulation settings - self.sim.physics_manager_cfg.dt = 0.01 # 100Hz + self.sim.physics.dt = 0.01 # 100Hz self.sim.render_interval = 5 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/stack_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/stack_env_cfg.py index dcda26f6e54..8efcf500ea4 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/stack_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/stack_env_cfg.py @@ -189,10 +189,10 @@ def __post_init__(self): self.decimation = 5 self.episode_length_s = 30.0 # simulation settings - self.sim.physics_manager_cfg.dt = 0.01 # 100Hz + self.sim.physics.dt = 0.01 # 100Hz self.sim.render_interval = 2 - self.sim.physics_manager_cfg.bounce_threshold_velocity = 0.01 - self.sim.physics_manager_cfg.gpu_found_lost_aggregate_pairs_capacity = 1024 * 1024 * 4 - self.sim.physics_manager_cfg.gpu_total_aggregate_pairs_capacity = 16 * 1024 - self.sim.physics_manager_cfg.friction_correlation_distance = 0.00625 + self.sim.physics.bounce_threshold_velocity = 0.01 + self.sim.physics.gpu_found_lost_aggregate_pairs_capacity = 1024 * 1024 * 4 + self.sim.physics.gpu_total_aggregate_pairs_capacity = 16 * 1024 + self.sim.physics.friction_correlation_distance = 0.00625 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/stack_instance_randomize_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/stack_instance_randomize_env_cfg.py index 2ecacf6d129..2000ba4ce9d 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/stack_instance_randomize_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/stack_instance_randomize_env_cfg.py @@ -125,10 +125,10 @@ def __post_init__(self): self.decimation = 5 self.episode_length_s = 30.0 # simulation settings - self.sim.physics_manager_cfg.dt = 0.01 # 100Hz + self.sim.physics.dt = 0.01 # 100Hz self.sim.render_interval = self.decimation - self.sim.physics_manager_cfg.bounce_threshold_velocity = 0.01 - self.sim.physics_manager_cfg.gpu_found_lost_aggregate_pairs_capacity = 1024 * 1024 * 4 - self.sim.physics_manager_cfg.gpu_total_aggregate_pairs_capacity = 16 * 1024 - self.sim.physics_manager_cfg.friction_correlation_distance = 0.00625 + self.sim.physics.bounce_threshold_velocity = 0.01 + self.sim.physics.gpu_found_lost_aggregate_pairs_capacity = 1024 * 1024 * 4 + self.sim.physics.gpu_total_aggregate_pairs_capacity = 16 * 1024 + self.sim.physics.friction_correlation_distance = 0.00625 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/navigation/config/anymal_c/navigation_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/navigation/config/anymal_c/navigation_env_cfg.py index 26a69a3b2d5..b0091dcd7fd 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/navigation/config/anymal_c/navigation_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/navigation/config/anymal_c/navigation_env_cfg.py @@ -135,17 +135,17 @@ class NavigationEnvCfg(ManagerBasedRLEnvCfg): def __post_init__(self): """Post initialization.""" - self.sim.physics_manager_cfg.dt = LOW_LEVEL_ENV_CFG.sim.physics_manager_cfg.dt + self.sim.physics.dt = LOW_LEVEL_ENV_CFG.sim.physics.dt self.sim.render_interval = LOW_LEVEL_ENV_CFG.decimation self.decimation = LOW_LEVEL_ENV_CFG.decimation * 10 self.episode_length_s = self.commands.pose_command.resampling_time_range[1] if self.scene.height_scanner is not None: self.scene.height_scanner.update_period = ( - self.actions.pre_trained_policy_action.low_level_decimation * self.sim.physics_manager_cfg.dt + self.actions.pre_trained_policy_action.low_level_decimation * self.sim.physics.dt ) if self.scene.contact_forces is not None: - self.scene.contact_forces.update_period = self.sim.physics_manager_cfg.dt + self.scene.contact_forces.update_period = self.sim.physics.dt class NavigationEnvCfg_PLAY(NavigationEnvCfg): From 433226246febe31fcffcdcf3d85325b911110ec1 Mon Sep 17 00:00:00 2001 From: Octi Zhang Date: Sun, 8 Feb 2026 20:23:34 -0800 Subject: [PATCH 25/46] fixed many test bugs --- .../isaaclab/isaaclab/envs/direct_marl_env.py | 4 +- .../isaaclab/isaaclab/envs/direct_rl_env.py | 15 +- .../isaaclab/envs/manager_based_env.py | 13 +- .../isaaclab/envs/manager_based_rl_env.py | 6 +- .../isaaclab/physics/physics_manager.py | 12 +- .../isaaclab/sim/simulation_context.py | 24 +-- source/isaaclab/isaaclab/sim/utils/prims.py | 1 - source/isaaclab/isaaclab/sim/utils/stage.py | 125 +++++++++++++--- .../isaaclab/sim/views/xform_prim_view.py | 3 - .../test/devices/test_device_constructors.py | 39 +++-- .../test/envs/test_env_rendering_logic.py | 141 ++++++++++-------- .../test/managers/test_recorder_manager.py | 8 + source/isaaclab/test/sensors/test_camera.py | 5 +- .../test_multi_mesh_ray_caster_camera.py | 3 +- .../test/sensors/test_multi_tiled_camera.py | 9 +- .../test/sensors/test_ray_caster_camera.py | 13 +- .../test/sensors/test_tiled_camera.py | 42 +++--- .../test/sim/test_simulation_context.py | 2 +- .../test/sim/test_simulation_render_config.py | 11 +- .../sim/test_simulation_stage_in_memory.py | 35 ++--- .../test/sensors/test_visuotactile_sensor.py | 3 +- .../isaaclab_physx/physics/physx_manager.py | 24 ++- .../visualizers/ov_visualizer.py | 135 +++++++++++++++++ 23 files changed, 470 insertions(+), 203 deletions(-) diff --git a/source/isaaclab/isaaclab/envs/direct_marl_env.py b/source/isaaclab/isaaclab/envs/direct_marl_env.py index 381a0dc45e7..3029a22a561 100644 --- a/source/isaaclab/isaaclab/envs/direct_marl_env.py +++ b/source/isaaclab/isaaclab/envs/direct_marl_env.py @@ -213,7 +213,7 @@ def __init__(self, cfg: DirectMARLEnvCfg, render_mode: str | None = None, **kwar if "startup" in self.event_manager.available_modes: self.event_manager.apply(mode="startup") - + self.has_rtx_sensors = self.sim.get_setting("/isaaclab/render/rtx_sensors") # print the environment information print("[INFO]: Completed setting up the environment...") @@ -492,7 +492,7 @@ def render(self, recompute: bool = False) -> np.ndarray | None: """ # run a rendering step of the simulator # if we have rtx sensors, we do not need to render again since step already rendered - if not self.sim.has_rtx_sensors and not recompute: + if not self.has_rtx_sensors and not recompute: self.sim.render() # decide the rendering mode if self.render_mode == "human" or self.render_mode is None: diff --git a/source/isaaclab/isaaclab/envs/direct_rl_env.py b/source/isaaclab/isaaclab/envs/direct_rl_env.py index 5b4567acda0..17d29f7ebd8 100644 --- a/source/isaaclab/isaaclab/envs/direct_rl_env.py +++ b/source/isaaclab/isaaclab/envs/direct_rl_env.py @@ -221,7 +221,7 @@ def __init__(self, cfg: DirectRLEnvCfg, render_mode: str | None = None, **kwargs # set the framerate of the gym video recorder wrapper so that the playback speed of the produced # video matches the simulation self.metadata["render_fps"] = 1 / self.step_dt - + self.has_rtx_sensors = self.sim.get_setting("/isaaclab/render/rtx_sensors") # show deprecation message for rerender_on_reset if self.cfg.rerender_on_reset: msg = ( @@ -317,15 +317,14 @@ def reset(self, seed: int | None = None, options: dict[str, Any] | None = None) self.sim.forward() # if sensors are added to the scene, make sure we render to reflect changes in reset - if self.sim.has_rtx_sensors and self.cfg.num_rerenders_on_reset > 0: + if self.has_rtx_sensors and self.cfg.num_rerenders_on_reset > 0: for _ in range(self.cfg.num_rerenders_on_reset): self.sim.render() - if self.cfg.wait_for_textures and self.sim.has_rtx_sensors: + if self.cfg.wait_for_textures and self.has_rtx_sensors: # Wait for assets to finish loading (PhysX-specific) - pm = self.sim.physics_manager - if hasattr(pm, "assets_loading"): - while pm.assets_loading(): + if hasattr(self.sim.physics_manager, "assets_loading"): + while self.sim.physics_manager.assets_loading(): self.sim.render() # return observations @@ -398,7 +397,7 @@ def step(self, action: torch.Tensor) -> VecEnvStepReturn: if len(reset_env_ids) > 0: self._reset_idx(reset_env_ids) # if sensors are added to the scene, make sure we render to reflect changes in reset - if self.sim.has_rtx_sensors and self.cfg.num_rerenders_on_reset > 0: + if self.has_rtx_sensors and self.cfg.num_rerenders_on_reset > 0: for _ in range(self.cfg.num_rerenders_on_reset): self.sim.render() @@ -462,7 +461,7 @@ def render(self, recompute: bool = False) -> np.ndarray | None: """ # run a rendering step of the simulator # if we have rtx sensors, we do not need to render again since step already rendered - if not self.sim.has_rtx_sensors and not recompute: + if not self.has_rtx_sensors and not recompute: self.sim.render() # decide the rendering mode if self.render_mode == "human" or self.render_mode is None: diff --git a/source/isaaclab/isaaclab/envs/manager_based_env.py b/source/isaaclab/isaaclab/envs/manager_based_env.py index 45a3d19591e..dc818f3b999 100644 --- a/source/isaaclab/isaaclab/envs/manager_based_env.py +++ b/source/isaaclab/isaaclab/envs/manager_based_env.py @@ -185,7 +185,7 @@ def __init__(self, cfg: ManagerBasedEnvCfg): else: # if no window, then we don't need to store the window self._window = None - + self.has_rtx_sensors = self.sim.get_setting("/isaaclab/render/rtx_sensors") # initialize observation buffers self.obs_buf = {} @@ -371,7 +371,7 @@ def reset( self.scene.write_data_to_sim() self.sim.forward() # if sensors are added to the scene, make sure we render to reflect changes in reset - if self.sim.has_rtx_sensors and self.cfg.num_rerenders_on_reset > 0: + if self.has_rtx_sensors and self.cfg.num_rerenders_on_reset > 0: for _ in range(self.cfg.num_rerenders_on_reset): self.sim.render() @@ -381,11 +381,10 @@ def reset( # compute observations self.obs_buf = self.observation_manager.compute(update_history=True) - if self.cfg.wait_for_textures and self.sim.has_rtx_sensors: + if self.cfg.wait_for_textures and self.has_rtx_sensors: # Wait for assets to finish loading (PhysX-specific) - pm = self.sim.physics_manager - if hasattr(pm, "assets_loading"): - while pm.assets_loading(): + if hasattr(self.sim.physics_manager, "assets_loading"): + while self.sim.physics_manager.assets_loading(): self.sim.render() # return observations @@ -435,7 +434,7 @@ def reset_to( self.sim.forward() # if sensors are added to the scene, make sure we render to reflect changes in reset - if self.sim.has_rtx_sensors and self.cfg.num_rerenders_on_reset > 0: + if self.has_rtx_sensors and self.cfg.num_rerenders_on_reset > 0: for _ in range(self.cfg.num_rerenders_on_reset): self.sim.render() diff --git a/source/isaaclab/isaaclab/envs/manager_based_rl_env.py b/source/isaaclab/isaaclab/envs/manager_based_rl_env.py index 02e25373ab3..eb80c75d80b 100644 --- a/source/isaaclab/isaaclab/envs/manager_based_rl_env.py +++ b/source/isaaclab/isaaclab/envs/manager_based_rl_env.py @@ -85,7 +85,7 @@ def __init__(self, cfg: ManagerBasedRLEnvCfg, render_mode: str | None = None, ** # -- set the framerate of the gym video recorder wrapper so that the playback speed of the # produced video matches the simulation self.metadata["render_fps"] = 1 / self.step_dt - + self.has_rtx_sensors = self.sim.get_setting("/isaaclab/render/rtx_sensors") print("[INFO]: Completed setting up the environment...") """ @@ -221,7 +221,7 @@ def step(self, action: torch.Tensor) -> VecEnvStepReturn: self._reset_idx(reset_env_ids) # if sensors are added to the scene, make sure we render to reflect changes in reset - if self.sim.has_rtx_sensors and self.cfg.num_rerenders_on_reset > 0: + if self.has_rtx_sensors and self.cfg.num_rerenders_on_reset > 0: for _ in range(self.cfg.num_rerenders_on_reset): self.sim.render() @@ -264,7 +264,7 @@ def render(self, recompute: bool = False) -> np.ndarray | None: """ # run a rendering step of the simulator # if we have rtx sensors, we do not need to render again since step already rendered - if not self.sim.has_rtx_sensors and not recompute: + if not self.has_rtx_sensors and not recompute: self.sim.render() # decide the rendering mode if self.render_mode == "human" or self.render_mode is None: diff --git a/source/isaaclab/isaaclab/physics/physics_manager.py b/source/isaaclab/isaaclab/physics/physics_manager.py index 3d176d182f0..7143867bb03 100644 --- a/source/isaaclab/isaaclab/physics/physics_manager.py +++ b/source/isaaclab/isaaclab/physics/physics_manager.py @@ -24,10 +24,10 @@ class PhysicsEvent(Enum): """Physics simulation lifecycle events. These are general events that apply across all physics backends. - Backend-specific events (e.g., PhysX timeline events) are handled - by the respective manager classes. + Backend-specific events (e.g., PhysX step events, timeline events) are handled + by the respective manager classes via their own event enums (e.g., IsaacEvents). - Lifecycle order: MODEL_INIT -> PHYSICS_READY -> (PRE_STEP -> POST_STEP)* -> STOP + Lifecycle order: MODEL_INIT -> PHYSICS_READY -> STOP """ MODEL_INIT = "model_init" @@ -42,12 +42,6 @@ class PhysicsEvent(Enum): ready to step. Assets can now read initial state (positions, velocities). """ - PRE_STEP = "pre_step" - """About to advance physics by one timestep.""" - - POST_STEP = "post_step" - """Called after each physics step.""" - STOP = "stop" """Simulation is stopping.""" diff --git a/source/isaaclab/isaaclab/sim/simulation_context.py b/source/isaaclab/isaaclab/sim/simulation_context.py index d2698ed9102..318976cd6f2 100644 --- a/source/isaaclab/isaaclab/sim/simulation_context.py +++ b/source/isaaclab/isaaclab/sim/simulation_context.py @@ -92,10 +92,15 @@ def __init__(self, cfg: SimulationCfg | None = None): # Store config self.cfg = SimulationCfg() if cfg is None else cfg - # Get existing stage or create new one in memory + # Get or create stage based on config stage_cache = UsdUtils.StageCache.Get() - all_stages = stage_cache.GetAllStages() if stage_cache.Size() > 0 else [] # type: ignore[union-attr] - self.stage = all_stages[0] if all_stages else create_new_stage_in_memory() + if self.cfg.create_stage_in_memory: + # Create a fresh in-memory stage (not attached to USD context) + self.stage = create_new_stage_in_memory() + else: + # Use existing stage from cache, or create in-memory as fallback + all_stages = stage_cache.GetAllStages() if stage_cache.Size() > 0 else [] # type: ignore[union-attr] + self.stage = all_stages[0] if all_stages else create_new_stage_in_memory() # Cache stage in USD cache stage_id = stage_cache.GetId(self.stage).ToLongInt() # type: ignore[union-attr] @@ -120,8 +125,8 @@ def __init__(self, cfg: SimulationCfg | None = None): # Cache commonly-used settings (these don't change during runtime) self._has_gui = bool(self.get_setting("/isaaclab/has_gui")) - self._has_rtx_sensors = bool(self.get_setting("/isaaclab/render/rtx_sensors")) self._has_offscreen_render = bool(self.get_setting("/isaaclab/render/offscreen")) + # Note: has_rtx_sensors is NOT cached because it changes when Camera sensors are created # Simulation state self._is_playing = False @@ -180,11 +185,6 @@ def has_gui(self) -> bool: """Returns whether GUI is enabled (cached at init).""" return self._has_gui - @property - def has_rtx_sensors(self) -> bool: - """Returns whether RTX sensors are enabled (cached at init).""" - return self._has_rtx_sensors - @property def has_offscreen_render(self) -> bool: """Returns whether offscreen rendering is enabled (cached at init).""" @@ -193,7 +193,7 @@ def has_offscreen_render(self) -> bool: @property def is_rendering(self) -> bool: """Returns whether rendering is active (GUI or RTX sensors).""" - return self._has_gui or self._has_rtx_sensors + return self._has_gui or self.get_setting("/isaaclab/render/rtx_sensors") def get_physics_dt(self) -> float: """Returns the physics time step.""" @@ -283,6 +283,10 @@ def render(self, mode: int | None = None) -> None: for viz in self._visualizers: if not viz.is_rendering_paused() and viz.is_running(): viz.step(self.get_rendering_dt(), state=None) + # Call render callbacks + if hasattr(self, "_render_callbacks"): + for callback in self._render_callbacks.values(): + callback(None) # Pass None as event data def play(self) -> None: """Start or resume the simulation.""" diff --git a/source/isaaclab/isaaclab/sim/utils/prims.py b/source/isaaclab/isaaclab/sim/utils/prims.py index 25e2b57855d..c7cfce4ca54 100644 --- a/source/isaaclab/isaaclab/sim/utils/prims.py +++ b/source/isaaclab/isaaclab/sim/utils/prims.py @@ -180,7 +180,6 @@ def create_prim( # this means that user provided pose in the world frame translation, orientation = convert_world_pose_to_local(position, orientation, ref_prim=prim.GetParent()) - print(f"translation: {translation}, orientation: {orientation}, scale: {scale}") # standardize the xform ops standardize_xform_ops(prim, translation, orientation, scale) diff --git a/source/isaaclab/isaaclab/sim/utils/stage.py b/source/isaaclab/isaaclab/sim/utils/stage.py index 3ec85448e61..3d1f9201a83 100644 --- a/source/isaaclab/isaaclab/sim/utils/stage.py +++ b/source/isaaclab/isaaclab/sim/utils/stage.py @@ -80,24 +80,65 @@ def create_new_stage_in_memory() -> Usd.Stage: return Usd.Stage.CreateInMemory() +def get_context_stage() -> Usd.Stage | None: + """Get the stage attached to the USD context, if any. + + The "context stage" is the USD stage attached to the Omniverse application's + UsdContext. This is the stage that: + + * The viewport renders + * The Stage panel in the UI displays + * Most Isaac Sim/Omniverse systems operate on by default + + This is different from an "in-memory stage" created via + :func:`create_new_stage_in_memory`, which exists only in RAM and is not + attached to the context (invisible to viewport/UI until explicitly attached + via :func:`attach_stage_to_usd_context`). + + Returns: + The stage attached to the USD context, or None if no stage is attached. + + Example: + >>> import isaaclab.sim as sim_utils + >>> + >>> stage = sim_utils.get_context_stage() + >>> if stage is not None: + ... print("Context has a stage attached") + """ + context = omni.usd.get_context() + if context is None: + return None + return context.get_stage() + + def is_current_stage_in_memory() -> bool: - """Checks if the current stage is in memory. + """Checks if the current stage is NOT attached to the USD context. - This function compares the stage id of the current USD stage with the stage id of the USD context stage. + This function compares the current stage (from :func:`get_current_stage`) with + the context stage (from :func:`get_context_stage`). If they are different, + the current stage is considered "in memory" - meaning it's not the stage + that the viewport/UI displays. + + This is useful for determining if we're working with a separate in-memory + stage created via :func:`create_new_stage_in_memory` with + ``SimulationCfg(create_stage_in_memory=True)``. Returns: - Whether the current stage is in memory. + True if the current stage is different from (not attached to) the context stage. + Also returns True if there is no context stage at all. """ - # grab current stage id - stage_id = get_current_stage_id() + # Get current stage + current_stage = get_current_stage() + context_stage = get_context_stage() - # grab context stage id - context_stage = omni.usd.get_context().get_stage() - with use_stage(context_stage): - context_stage_id = get_current_stage_id() + # If no context stage exists, current stage is definitely not attached to it + if context_stage is None: + return True - # check if stage ids are the same - return stage_id != context_stage_id + # Compare by identity - are they the same stage object? + # Note: We can't just compare IDs because different stage objects could + # theoretically have the same ID if one was closed and another opened. + return current_stage is not context_stage def open_stage(usd_path: str) -> bool: @@ -182,24 +223,54 @@ def use_stage(stage: Usd.Stage) -> Generator[None, None, None]: def update_stage() -> None: - """Updates the current stage by triggering an application update cycle. - - This function triggers a single update cycle of the application interface, which - in turn updates the stage and all associated systems (rendering, physics, etc.). - This is necessary to ensure that changes made to the stage are properly processed - and reflected in the simulation. - - Note: - This function calls the application update interface rather than directly - updating the stage because the stage update is part of the broader - application update cycle that includes rendering, physics, and other systems. + """Triggers a full application update cycle to process USD stage changes. + + This function calls ``omni.kit.app.get_app_interface().update()`` which triggers + a complete application update including: + + * Physics simulation step (if ``/app/player/playSimulations`` is True) + * Rendering (RTX path tracing, viewport updates) + * UI updates (widgets, windows) + * Timeline events and callbacks + * Extension updates + * USD/Fabric synchronization + + When to Use: + * **After creating a new stage**: ``create_new_stage()`` → ``update_stage()`` + * **After spawning prims**: ``cfg.func("/World/Robot", cfg)`` → ``update_stage()`` + * **After USD authoring**: Creating materials, lights, meshes, etc. + * **Before simulation starts**: During setup phase, before ``sim.reset()`` + * **In test fixtures**: To ensure consistent state before each test + + When NOT to Use: + * **During active simulation** (after ``sim.play()``): Can interfere with + physics stepping and cause double-stepping or timing issues. + * **During sensor updates**: Can reset RTX renderer state mid-cycle, + causing incorrect sensor outputs (e.g., ``inf`` depth values). + * **Inside physics/render callbacks**: Can cause recursion or timing issues. + * **Inside ``sim.step()`` or ``sim.render()``**: These already perform + app updates internally with proper safeguards. + + For rendering during simulation without physics stepping, use:: + + sim.set_setting("/app/player/playSimulations", False) + omni.kit.app.get_app().update() + sim.set_setting("/app/player/playSimulations", True) Example: >>> import isaaclab.sim as sim_utils >>> - >>> sim_utils.update_stage() + >>> # Setup phase - safe to use + >>> sim_utils.create_new_stage() + >>> robot_cfg.func("/World/Robot", robot_cfg) + >>> sim_utils.update_stage() # Commit USD changes + >>> + >>> # Simulation phase - DO NOT use update_stage() + >>> sim.reset() + >>> sim.play() + >>> for _ in range(100): + ... sim.step() # Handles updates internally """ - # TODO: Why is this updating the simulation and not the stage? omni.kit.app.get_app_interface().update() @@ -426,11 +497,17 @@ def get_current_stage_id() -> int: """ # get current stage stage = get_current_stage() + if stage is None: + raise RuntimeError("No current stage available. Did you create a stage?") + # retrieve stage ID from stage cache stage_cache = UsdUtils.StageCache.Get() stage_id = stage_cache.GetId(stage).ToLongInt() # if stage ID is not found, insert it into the stage cache if stage_id < 0: + # Ensure stage has a valid root layer before inserting + if not stage.GetRootLayer(): + raise RuntimeError("Stage has no root layer - cannot cache an incomplete stage.") stage_id = stage_cache.Insert(stage).ToLongInt() # return stage ID return stage_id diff --git a/source/isaaclab/isaaclab/sim/views/xform_prim_view.py b/source/isaaclab/isaaclab/sim/views/xform_prim_view.py index 7924a9c391b..1e5cda4bb5e 100644 --- a/source/isaaclab/isaaclab/sim/views/xform_prim_view.py +++ b/source/isaaclab/isaaclab/sim/views/xform_prim_view.py @@ -1083,9 +1083,6 @@ def _sync_fabric_from_usd_once(self) -> None: if not self._fabric_initialized: self._initialize_fabric() - # Ensure authored USD transforms are flushed before reading into Fabric. - sim_utils.update_stage() - # Read authoritative transforms from USD and write once into Fabric. positions_usd, orientations_usd = self._get_world_poses_usd() scales_usd = self._get_scales_usd() diff --git a/source/isaaclab/test/devices/test_device_constructors.py b/source/isaaclab/test/devices/test_device_constructors.py index dfc9e670c7f..8604d83e3a7 100644 --- a/source/isaaclab/test/devices/test_device_constructors.py +++ b/source/isaaclab/test/devices/test_device_constructors.py @@ -304,17 +304,20 @@ def test_openxr_constructors(mock_environment, mocker): { "carb": mock_environment["carb"], "omni.kit.xr.core": mock_environment["omni"].kit.xr.core, - "isaacsim.core.prims": mocker.MagicMock(), }, ) mocker.patch.object(device_mod, "carb", mock_environment["carb"]) mocker.patch.object(device_mod, "XRCore", mock_environment["omni"].kit.xr.core.XRCore) mocker.patch.object(device_mod, "XRPoseValidityFlags", mock_environment["omni"].kit.xr.core.XRPoseValidityFlags) - mock_single_xform = mocker.patch.object(device_mod, "SingleXFormPrim") - # Configure the mock to return a string for prim_path - mock_instance = mock_single_xform.return_value - mock_instance.prim_path = "/XRAnchor" + # Mock sim_utils functions used by OpenXRDevice + mock_stage = mocker.MagicMock() + mock_prim = mocker.MagicMock() + mock_prim.IsValid.return_value = False # Prim doesn't exist, so create_prim will be called + mock_stage.GetPrimAtPath.return_value = mock_prim + mocker.patch.object(device_mod, "sim_utils", mocker.MagicMock()) + device_mod.sim_utils.get_current_stage.return_value = mock_stage + device_mod.sim_utils.create_prim.return_value = None # Create the device using the factory device = OpenXRDevice(config) @@ -527,17 +530,20 @@ def test_create_teleop_device_with_callbacks(mock_environment, mocker): { "carb": mock_environment["carb"], "omni.kit.xr.core": mock_environment["omni"].kit.xr.core, - "isaacsim.core.prims": mocker.MagicMock(), }, ) mocker.patch.object(device_mod, "carb", mock_environment["carb"]) mocker.patch.object(device_mod, "XRCore", mock_environment["omni"].kit.xr.core.XRCore) mocker.patch.object(device_mod, "XRPoseValidityFlags", mock_environment["omni"].kit.xr.core.XRPoseValidityFlags) - mock_single_xform = mocker.patch.object(device_mod, "SingleXFormPrim") - # Configure the mock to return a string for prim_path - mock_instance = mock_single_xform.return_value - mock_instance.prim_path = "/XRAnchor" + # Mock sim_utils functions used by OpenXRDevice + mock_stage = mocker.MagicMock() + mock_prim = mocker.MagicMock() + mock_prim.IsValid.return_value = False # Prim doesn't exist, so create_prim will be called + mock_stage.GetPrimAtPath.return_value = mock_prim + mocker.patch.object(device_mod, "sim_utils", mocker.MagicMock()) + device_mod.sim_utils.get_current_stage.return_value = mock_stage + device_mod.sim_utils.create_prim.return_value = None # Create the device using the factory device = create_teleop_device("test_xr", devices_cfg, callbacks) @@ -569,17 +575,20 @@ def test_create_teleop_device_with_retargeters(mock_environment, mocker): { "carb": mock_environment["carb"], "omni.kit.xr.core": mock_environment["omni"].kit.xr.core, - "isaacsim.core.prims": mocker.MagicMock(), }, ) mocker.patch.object(device_mod, "carb", mock_environment["carb"]) mocker.patch.object(device_mod, "XRCore", mock_environment["omni"].kit.xr.core.XRCore) mocker.patch.object(device_mod, "XRPoseValidityFlags", mock_environment["omni"].kit.xr.core.XRPoseValidityFlags) - mock_single_xform = mocker.patch.object(device_mod, "SingleXFormPrim") - # Configure the mock to return a string for prim_path - mock_instance = mock_single_xform.return_value - mock_instance.prim_path = "/XRAnchor" + # Mock sim_utils functions used by OpenXRDevice + mock_stage = mocker.MagicMock() + mock_prim = mocker.MagicMock() + mock_prim.IsValid.return_value = False # Prim doesn't exist, so create_prim will be called + mock_stage.GetPrimAtPath.return_value = mock_prim + mocker.patch.object(device_mod, "sim_utils", mocker.MagicMock()) + device_mod.sim_utils.get_current_stage.return_value = mock_stage + device_mod.sim_utils.create_prim.return_value = None # Create the device using the factory device = create_teleop_device("test_xr", devices_cfg) diff --git a/source/isaaclab/test/envs/test_env_rendering_logic.py b/source/isaaclab/test/envs/test_env_rendering_logic.py index e20c4255387..1fdfbbbb244 100644 --- a/source/isaaclab/test/envs/test_env_rendering_logic.py +++ b/source/isaaclab/test/envs/test_env_rendering_logic.py @@ -15,11 +15,10 @@ import pytest import torch -from isaaclab_physx.physics import PhysxCfg +from isaaclab_physx.physics import IsaacEvents, PhysxCfg from isaaclab_physx.visualizers import RenderMode -import omni.usd - +import isaaclab.sim as sim_utils from isaaclab.envs import ( DirectRLEnv, DirectRLEnvCfg, @@ -29,7 +28,7 @@ ManagerBasedRLEnvCfg, ) from isaaclab.scene import InteractiveSceneCfg -from isaaclab.sim import SimulationCfg +from isaaclab.sim import SimulationCfg, SimulationContext from isaaclab.utils import configclass @@ -131,9 +130,9 @@ def render_callback(): render_time = 0.0 num_render_steps = 0 - def callback(event): + def callback(dt): nonlocal render_time, num_render_steps - render_time += event.payload["dt"] + render_time += dt num_render_steps += 1 return callback, lambda: (render_time, num_render_steps) @@ -146,9 +145,15 @@ def test_env_rendering_logic(env_type, render_interval, physics_callback, render physics_cb, get_physics_stats = physics_callback render_cb, get_render_stats = render_callback - # create a new stage - omni.usd.get_context().new_stage() + env = None + physics_handle = None + original_step = None + viz = None + try: + # create a new stage + sim_utils.create_new_stage() + # create environment if env_type == "manager_based_env": env = create_manager_based_env(render_interval) @@ -156,56 +161,74 @@ def test_env_rendering_logic(env_type, render_interval, physics_callback, render env = create_manager_based_rl_env(render_interval) else: env = create_direct_rl_env(render_interval) - except Exception as e: - if "env" in locals() and hasattr(env, "_is_closed"): - env.close() - else: - if hasattr(e, "obj") and hasattr(e.obj, "_is_closed"): - e.obj.close() - pytest.fail(f"Failed to set-up the environment {env_type}. Error: {e}") - - # enable the flag to render the environment - # note: this is only done for the unit testing to "fake" camera rendering. - # normally this is set to True when cameras are created. - env.sim.set_setting("/isaaclab/render/rtx_sensors", True) - - # disable the app from shutting down when the environment is closed - # FIXME: Why is this needed in this test but not in the other tests? - # Without it, the test will exit after the environment is closed - env.sim._app_control_on_stop_handle = None # type: ignore - - # check that we are in partial rendering mode for the environment - # this is enabled due to app launcher setting "enable_cameras=True" - # Access render mode through the first visualizer (OVVisualizer) - assert env.sim.visualizers[0].render_mode == RenderMode.PARTIAL_RENDERING - - # add physics and render callbacks - env.sim.add_physics_callback("physics_step", physics_cb) - env.sim.add_render_callback("render_step", render_cb) - - # create a zero action tensor for stepping the environment - actions = torch.zeros((env.num_envs, 0), device=env.device) - - # run the environment and check the rendering logic - for i in range(50): - # apply zero actions - env.step(action=actions) - - # check that we have completed the correct number of physics steps - _, num_physics_steps = get_physics_stats() - assert num_physics_steps == (i + 1) * env.cfg.decimation, "Physics steps mismatch" - # check that we have simulated physics for the correct amount of time - physics_time, _ = get_physics_stats() - assert abs(physics_time - num_physics_steps * env.cfg.sim.dt) < 1e-6, "Physics time mismatch" - - # check that we have completed the correct number of rendering steps - _, num_render_steps = get_render_stats() - assert num_render_steps == (i + 1) * env.cfg.decimation // env.cfg.sim.render_interval, "Render steps mismatch" - # check that we have rendered for the correct amount of time - render_time, _ = get_render_stats() - assert abs(render_time - num_render_steps * env.cfg.sim.dt * env.cfg.sim.render_interval) < 1e-6, ( - "Render time mismatch" + + # enable the flag to render the environment + # note: this is only done for the unit testing to "fake" camera rendering. + # normally this is set to True when cameras are created. + env.sim.set_setting("/isaaclab/render/rtx_sensors", True) + + # disable the app from shutting down when the environment is closed + # FIXME: Why is this needed in this test but not in the other tests? + # Without it, the test will exit after the environment is closed + env.sim._app_control_on_stop_handle = None # type: ignore + + # check that we are in partial rendering mode for the environment + # this is enabled due to app launcher setting "enable_cameras=True" + # Access render mode through the first visualizer (OVVisualizer) + assert env.sim.visualizers[0].render_mode == RenderMode.PARTIAL_RENDERING + + # add physics callback via physics manager (IsaacEvents is PhysX-specific) + physics_handle = env.sim.physics_manager.register_callback( + physics_cb, IsaacEvents.POST_PHYSICS_STEP, name="physics_step" ) - # close the environment - env.close() + # Wrap visualizer step to track render calls + viz = env.sim.visualizers[0] + original_step = viz.step + render_dt = env.cfg.sim.dt * env.cfg.sim.render_interval + + def wrapped_step(dt, state=None): + original_step(dt, state) + render_cb(render_dt) + + viz.step = wrapped_step + + # create a zero action tensor for stepping the environment + actions = torch.zeros((env.num_envs, 0), device=env.device) + + # run the environment and check the rendering logic + for i in range(50): + # apply zero actions + env.step(action=actions) + + # check that we have completed the correct number of physics steps + _, num_physics_steps = get_physics_stats() + assert num_physics_steps == (i + 1) * env.cfg.decimation, "Physics steps mismatch" + # check that we have simulated physics for the correct amount of time + physics_time, _ = get_physics_stats() + assert abs(physics_time - num_physics_steps * env.cfg.sim.dt) < 1e-6, "Physics time mismatch" + + # check that we have completed the correct number of rendering steps + _, num_render_steps = get_render_stats() + assert num_render_steps == (i + 1) * env.cfg.decimation // env.cfg.sim.render_interval, ( + "Render steps mismatch" + ) + # check that we have rendered for the correct amount of time + render_time, _ = get_render_stats() + assert abs(render_time - num_render_steps * env.cfg.sim.dt * env.cfg.sim.render_interval) < 1e-6, ( + "Render time mismatch" + ) + + finally: + # Restore original step method + if viz is not None and original_step is not None: + viz.step = original_step + # Deregister physics callback + if physics_handle is not None: + physics_handle.deregister() + # Close environment (this also clears SimulationContext) + if env is not None: + env.close() + else: + # If env creation failed, still clear the singleton + SimulationContext.clear_instance() diff --git a/source/isaaclab/test/managers/test_recorder_manager.py b/source/isaaclab/test/managers/test_recorder_manager.py index 8a8e8c78a9d..61264acfdbc 100644 --- a/source/isaaclab/test/managers/test_recorder_manager.py +++ b/source/isaaclab/test/managers/test_recorder_manager.py @@ -198,6 +198,14 @@ def dataset_dir(): shutil.rmtree(test_dir) +@pytest.fixture(autouse=True) +def cleanup_simulation_context(): + """Fixture to ensure SimulationContext is cleared after each test.""" + yield + # Cleanup after test + SimulationContext.clear_instance() + + def test_str(dataset_dir): """Test the string representation of the recorder manager.""" # create recorder manager diff --git a/source/isaaclab/test/sensors/test_camera.py b/source/isaaclab/test/sensors/test_camera.py index 967dcc88818..e42add9ff93 100644 --- a/source/isaaclab/test/sensors/test_camera.py +++ b/source/isaaclab/test/sensors/test_camera.py @@ -77,8 +77,7 @@ def teardown(sim: sim_utils.SimulationContext): # close all the opened viewport from before. rep.vp_manager.destroy_hydra_textures("Replicator") # stop simulation - # note: cannot use self.sim.stop() since it does one render step after stopping!! This doesn't make sense :( - sim._timeline.stop() + sim.stop() # clear the stage sim.clear_instance() @@ -98,7 +97,7 @@ def test_camera_init(setup_sim_camera): # Create camera camera = Camera(camera_cfg) # Check simulation parameter is set correctly - assert sim.has_rtx_sensors() + assert sim.get_setting("/isaaclab/render/rtx_sensors") # Play sim sim.reset() # Check if camera is initialized diff --git a/source/isaaclab/test/sensors/test_multi_mesh_ray_caster_camera.py b/source/isaaclab/test/sensors/test_multi_mesh_ray_caster_camera.py index 57301e82d16..32342c7238b 100644 --- a/source/isaaclab/test/sensors/test_multi_mesh_ray_caster_camera.py +++ b/source/isaaclab/test/sensors/test_multi_mesh_ray_caster_camera.py @@ -82,8 +82,7 @@ def setup_simulation(): # close all the opened viewport from before. rep.vp_manager.destroy_hydra_textures("Replicator") # stop simulation - # note: cannot use self.sim.stop() since it does one render step after stopping!! This doesn't make sense :( - sim._timeline.stop() + sim.stop() # clear the stage sim.clear_instance() diff --git a/source/isaaclab/test/sensors/test_multi_tiled_camera.py b/source/isaaclab/test/sensors/test_multi_tiled_camera.py index 4b332ae2921..5d6b2f820a1 100644 --- a/source/isaaclab/test/sensors/test_multi_tiled_camera.py +++ b/source/isaaclab/test/sensors/test_multi_tiled_camera.py @@ -60,8 +60,7 @@ def setup_camera(): # Teardown rep.vp_manager.destroy_hydra_textures("Replicator") # stop simulation - # note: cannot use self.sim.stop() since it does one render step after stopping!! This doesn't make sense :( - sim._timeline.stop() + sim.stop() # clear the stage sim.clear_instance() @@ -85,7 +84,7 @@ def test_multi_tiled_camera_init(setup_camera): tiled_cameras.append(camera) # Check simulation parameter is set correctly - assert sim.has_rtx_sensors() + assert sim.get_setting("/isaaclab/render/rtx_sensors") # Play sim sim.reset() @@ -182,7 +181,7 @@ def test_all_annotators_multi_tiled_camera(setup_camera): tiled_cameras.append(camera) # Check simulation parameter is set correctly - assert sim.has_rtx_sensors() + assert sim.get_setting("/isaaclab/render/rtx_sensors") # Play sim sim.reset() @@ -285,7 +284,7 @@ def test_different_resolution_multi_tiled_camera(setup_camera): tiled_cameras.append(camera) # Check simulation parameter is set correctly - assert sim.has_rtx_sensors() + assert sim.get_setting("/isaaclab/render/rtx_sensors") # Play sim sim.reset() diff --git a/source/isaaclab/test/sensors/test_ray_caster_camera.py b/source/isaaclab/test/sensors/test_ray_caster_camera.py index ea90338004d..009cd2e0fbc 100644 --- a/source/isaaclab/test/sensors/test_ray_caster_camera.py +++ b/source/isaaclab/test/sensors/test_ray_caster_camera.py @@ -72,9 +72,13 @@ def setup() -> tuple[sim_utils.SimulationContext, RayCasterCameraCfg, float]: # Load kit helper sim_cfg = sim_utils.SimulationCfg(physics=PhysxCfg(dt=dt)) sim = sim_utils.SimulationContext(sim_cfg) - # Ground-plane + # Ground-plane with visual material for RTX rendering compatibility mesh = make_plane(size=(100, 100), height=0.0, center_zero=True) - create_prim_from_mesh("/World/defaultGroundPlane", mesh) + visual_material = sim_utils.PreviewSurfaceCfg(diffuse_color=(0.5, 0.5, 0.5)) + create_prim_from_mesh("/World/defaultGroundPlane", mesh, visual_material=visual_material) + # Add lighting for RTX rendering + light_cfg = sim_utils.DomeLightCfg(intensity=2000.0) + light_cfg.func("/World/Light", light_cfg) # load stage sim_utils.update_stage() return sim, camera_cfg, dt @@ -85,8 +89,7 @@ def teardown(sim: sim_utils.SimulationContext): # close all the opened viewport from before. rep.vp_manager.destroy_hydra_textures("Replicator") # stop simulation - # note: cannot use self.sim.stop() since it does one render step after stopping!! This doesn't make sense :( - sim._timeline.stop() + sim.stop() # clear the stage sim.clear_instance() @@ -581,6 +584,8 @@ def test_output_equal_to_usdcamera(setup_sim): torch.testing.assert_close( camera_usd.data.output["distance_to_image_plane"], camera_warp.data.output["distance_to_image_plane"], + rtol=1e-5, + atol=1e-4, ) torch.testing.assert_close( camera_usd.data.output["distance_to_camera"], diff --git a/source/isaaclab/test/sensors/test_tiled_camera.py b/source/isaaclab/test/sensors/test_tiled_camera.py index 9ad199798dc..6092c32743f 100644 --- a/source/isaaclab/test/sensors/test_tiled_camera.py +++ b/source/isaaclab/test/sensors/test_tiled_camera.py @@ -60,7 +60,7 @@ def setup_camera(device) -> tuple[sim_utils.SimulationContext, TiledCameraCfg, f yield sim, camera_cfg, dt # Teardown rep.vp_manager.destroy_hydra_textures("Replicator") - sim._timeline.stop() + sim.stop() sim.clear_instance() @@ -72,7 +72,7 @@ def test_single_camera_init(setup_camera, device): # Create camera camera = TiledCamera(camera_cfg) # Check simulation parameter is set correctly - assert sim.has_rtx_sensors() + assert sim.get_setting("/isaaclab/render/rtx_sensors") # Play sim sim.reset() # Check if camera is initialized @@ -251,7 +251,7 @@ def test_multi_camera_init(setup_camera, device): camera_cfg.prim_path = "/World/Origin_.*/CameraSensor" camera = TiledCamera(camera_cfg) # Check simulation parameter is set correctly - assert sim.has_rtx_sensors() + assert sim.get_setting("/isaaclab/render/rtx_sensors") # Play sim sim.reset() # Check if camera is initialized @@ -308,7 +308,7 @@ def test_rgb_only_camera(setup_camera, device): camera_cfg.prim_path = "/World/Origin_.*/CameraSensor" camera = TiledCamera(camera_cfg) # Check simulation parameter is set correctly - assert sim.has_rtx_sensors() + assert sim.get_setting("/isaaclab/render/rtx_sensors") # Play sim sim.reset() # Check if camera is initialized @@ -410,7 +410,7 @@ def test_depth_only_camera(setup_camera, device): camera_cfg.prim_path = "/World/Origin_.*/CameraSensor" camera = TiledCamera(camera_cfg) # Check simulation parameter is set correctly - assert sim.has_rtx_sensors() + assert sim.get_setting("/isaaclab/render/rtx_sensors") # Play sim sim.reset() # Check if camera is initialized @@ -464,7 +464,7 @@ def test_rgba_only_camera(setup_camera, device): camera_cfg.prim_path = "/World/Origin_.*/CameraSensor" camera = TiledCamera(camera_cfg) # Check simulation parameter is set correctly - assert sim.has_rtx_sensors() + assert sim.get_setting("/isaaclab/render/rtx_sensors") # Play sim sim.reset() # Check if camera is initialized @@ -518,7 +518,7 @@ def test_albedo_only_camera(setup_camera, device): camera_cfg.prim_path = "/World/Origin_.*/CameraSensor" camera = TiledCamera(camera_cfg) # Check simulation parameter is set correctly - assert sim.has_rtx_sensors() + assert sim.get_setting("/isaaclab/render/rtx_sensors") # Play sim sim.reset() # Check if camera is initialized @@ -572,7 +572,7 @@ def test_distance_to_camera_only_camera(setup_camera, device): camera_cfg.prim_path = "/World/Origin_.*/CameraSensor" camera = TiledCamera(camera_cfg) # Check simulation parameter is set correctly - assert sim.has_rtx_sensors() + assert sim.get_setting("/isaaclab/render/rtx_sensors") # Play sim sim.reset() # Check if camera is initialized @@ -626,7 +626,7 @@ def test_distance_to_image_plane_only_camera(setup_camera, device): camera_cfg.prim_path = "/World/Origin_.*/CameraSensor" camera = TiledCamera(camera_cfg) # Check simulation parameter is set correctly - assert sim.has_rtx_sensors() + assert sim.get_setting("/isaaclab/render/rtx_sensors") # Play sim sim.reset() # Check if camera is initialized @@ -680,7 +680,7 @@ def test_normals_only_camera(setup_camera, device): camera_cfg.prim_path = "/World/Origin_.*/CameraSensor" camera = TiledCamera(camera_cfg) # Check simulation parameter is set correctly - assert sim.has_rtx_sensors() + assert sim.get_setting("/isaaclab/render/rtx_sensors") # Play sim sim.reset() # Check if camera is initialized @@ -737,7 +737,7 @@ def test_motion_vectors_only_camera(setup_camera, device): camera_cfg.prim_path = "/World/Origin_.*/CameraSensor" camera = TiledCamera(camera_cfg) # Check simulation parameter is set correctly - assert sim.has_rtx_sensors() + assert sim.get_setting("/isaaclab/render/rtx_sensors") # Play sim sim.reset() # Check if camera is initialized @@ -791,7 +791,7 @@ def test_semantic_segmentation_colorize_only_camera(setup_camera, device): camera_cfg.prim_path = "/World/Origin_.*/CameraSensor" camera = TiledCamera(camera_cfg) # Check simulation parameter is set correctly - assert sim.has_rtx_sensors() + assert sim.get_setting("/isaaclab/render/rtx_sensors") # Play sim sim.reset() # Check if camera is initialized @@ -846,7 +846,7 @@ def test_instance_segmentation_fast_colorize_only_camera(setup_camera, device): camera_cfg.prim_path = "/World/Origin_.*/CameraSensor" camera = TiledCamera(camera_cfg) # Check simulation parameter is set correctly - assert sim.has_rtx_sensors() + assert sim.get_setting("/isaaclab/render/rtx_sensors") # Play sim sim.reset() # Check if camera is initialized @@ -901,7 +901,7 @@ def test_instance_id_segmentation_fast_colorize_only_camera(setup_camera, device camera_cfg.prim_path = "/World/Origin_.*/CameraSensor" camera = TiledCamera(camera_cfg) # Check simulation parameter is set correctly - assert sim.has_rtx_sensors() + assert sim.get_setting("/isaaclab/render/rtx_sensors") # Play sim sim.reset() # Check if camera is initialized @@ -957,7 +957,7 @@ def test_semantic_segmentation_non_colorize_only_camera(setup_camera, device): camera_cfg.colorize_semantic_segmentation = False camera = TiledCamera(camera_cfg) # Check simulation parameter is set correctly - assert sim.has_rtx_sensors() + assert sim.get_setting("/isaaclab/render/rtx_sensors") # Play sim sim.reset() # Check if camera is initialized @@ -1014,7 +1014,7 @@ def test_instance_segmentation_fast_non_colorize_only_camera(setup_camera, devic camera_cfg.colorize_instance_segmentation = False camera = TiledCamera(camera_cfg) # Check simulation parameter is set correctly - assert sim.has_rtx_sensors() + assert sim.get_setting("/isaaclab/render/rtx_sensors") # Play sim sim.reset() # Check if camera is initialized @@ -1069,7 +1069,7 @@ def test_instance_id_segmentation_fast_non_colorize_only_camera(setup_camera, de camera_cfg.colorize_instance_id_segmentation = False camera = TiledCamera(camera_cfg) # Check simulation parameter is set correctly - assert sim.has_rtx_sensors() + assert sim.get_setting("/isaaclab/render/rtx_sensors") # Play sim sim.reset() # Check if camera is initialized @@ -1138,7 +1138,7 @@ def test_all_annotators_camera(setup_camera, device): camera_cfg.prim_path = "/World/Origin_.*/CameraSensor" camera = TiledCamera(camera_cfg) # Check simulation parameter is set correctly - assert sim.has_rtx_sensors() + assert sim.get_setting("/isaaclab/render/rtx_sensors") # Play sim sim.reset() # Check if camera is initialized @@ -1243,7 +1243,7 @@ def test_all_annotators_low_resolution_camera(setup_camera, device): camera_cfg.prim_path = "/World/Origin_.*/CameraSensor" camera = TiledCamera(camera_cfg) # Check simulation parameter is set correctly - assert sim.has_rtx_sensors() + assert sim.get_setting("/isaaclab/render/rtx_sensors") # Play sim sim.reset() # Check if camera is initialized @@ -1346,7 +1346,7 @@ def test_all_annotators_non_perfect_square_number_camera(setup_camera, device): camera_cfg.prim_path = "/World/Origin_.*/CameraSensor" camera = TiledCamera(camera_cfg) # Check simulation parameter is set correctly - assert sim.has_rtx_sensors() + assert sim.get_setting("/isaaclab/render/rtx_sensors") # Play sim sim.reset() # Check if camera is initialized @@ -1469,7 +1469,7 @@ def test_all_annotators_instanceable(setup_camera, device): camera_cfg.offset.pos = (0.0, 0.0, 5.5) camera = TiledCamera(camera_cfg) # Check simulation parameter is set correctly - assert sim.has_rtx_sensors() + assert sim.get_setting("/isaaclab/render/rtx_sensors") # Play sim sim.reset() # Check if camera is initialized diff --git a/source/isaaclab/test/sim/test_simulation_context.py b/source/isaaclab/test/sim/test_simulation_context.py index 0d9bb6700c6..88abe9ddab7 100644 --- a/source/isaaclab/test/sim/test_simulation_context.py +++ b/source/isaaclab/test/sim/test_simulation_context.py @@ -64,7 +64,7 @@ def test_init(device): # verify device property assert sim.device == device # verify no RTX sensors are available - assert not sim.has_rtx_sensors + assert not sim.get_setting("/isaaclab/render/rtx_sensors") # obtain physics scene from USD from pxr import UsdPhysics diff --git a/source/isaaclab/test/sim/test_simulation_render_config.py b/source/isaaclab/test/sim/test_simulation_render_config.py index 32738e2dd98..27c302e9708 100644 --- a/source/isaaclab/test/sim/test_simulation_render_config.py +++ b/source/isaaclab/test/sim/test_simulation_render_config.py @@ -105,6 +105,9 @@ def test_render_cfg_presets(): rendering_modes = ["performance", "balanced", "quality"] for rendering_mode in rendering_modes: + # Clear any existing simulation context before creating a new one + SimulationContext.clear_instance() + # grab isaac lab apps path isaaclab_app_exp_path = os.path.join(os.path.dirname(os.path.abspath(__file__)), *[".."] * 4, "apps") # for Isaac Sim 5 compatibility, we use the 5 rendering mode app files in a different folder @@ -143,7 +146,13 @@ def test_render_cfg_presets(): setting_val = carb_settings_iface.get(setting_name) - assert setting_gt == setting_val + assert setting_gt == setting_val, ( + f"Mismatch for '{setting_name}' in mode '{rendering_mode}': " + f"expected {setting_gt!r}, got {setting_val!r}" + ) + + # Clean up after the test + SimulationContext.clear_instance() @pytest.mark.skip(reason="Timeline not stopped") diff --git a/source/isaaclab/test/sim/test_simulation_stage_in_memory.py b/source/isaaclab/test/sim/test_simulation_stage_in_memory.py index 7691e419ccc..934fe9af1c8 100644 --- a/source/isaaclab/test/sim/test_simulation_stage_in_memory.py +++ b/source/isaaclab/test/sim/test_simulation_stage_in_memory.py @@ -18,9 +18,7 @@ import pytest -import omni import omni.physx -import omni.usd import usdrt from isaacsim.core.cloner import GridCloner @@ -117,11 +115,12 @@ def test_stage_in_memory_with_shapes(sim): prims = sim_utils.find_matching_prim_paths(prim_path_regex) assert len(prims) == num_clones - # verify prims do not exist in context stage - context_stage = omni.usd.get_context().get_stage() - with sim_utils.use_stage(context_stage): - prims = sim_utils.find_matching_prim_paths(prim_path_regex) - assert len(prims) != num_clones + # verify prims do not exist in context stage (if one exists) + context_stage = sim_utils.get_context_stage() + if context_stage is not None: + with sim_utils.use_stage(context_stage): + prims = sim_utils.find_matching_prim_paths(prim_path_regex) + assert len(prims) != num_clones # attach stage to context sim_utils.attach_stage_to_usd_context() @@ -182,11 +181,12 @@ def test_stage_in_memory_with_usds(sim): prims = sim_utils.find_matching_prim_paths(prim_path_regex) assert len(prims) == num_clones - # verify prims do not exist in context stage - context_stage = omni.usd.get_context().get_stage() - with sim_utils.use_stage(context_stage): - prims = sim_utils.find_matching_prim_paths(prim_path_regex) - assert len(prims) != num_clones + # verify prims do not exist in context stage (if one exists) + context_stage = sim_utils.get_context_stage() + if context_stage is not None: + with sim_utils.use_stage(context_stage): + prims = sim_utils.find_matching_prim_paths(prim_path_regex) + assert len(prims) != num_clones # attach stage to context sim_utils.attach_stage_to_usd_context() @@ -237,11 +237,12 @@ def test_stage_in_memory_with_clone_in_fabric(sim): ) prim_path_regex = "/World/envs/env_.*" - # verify prims do not exist in context stage - context_stage = omni.usd.get_context().get_stage() - with sim_utils.use_stage(context_stage): - prims = sim_utils.find_matching_prim_paths(prim_path_regex) - assert len(prims) != num_clones + # verify prims do not exist in context stage (if one exists) + context_stage = sim_utils.get_context_stage() + if context_stage is not None: + with sim_utils.use_stage(context_stage): + prims = sim_utils.find_matching_prim_paths(prim_path_regex) + assert len(prims) != num_clones # attach stage to context sim_utils.attach_stage_to_usd_context() diff --git a/source/isaaclab_contrib/test/sensors/test_visuotactile_sensor.py b/source/isaaclab_contrib/test/sensors/test_visuotactile_sensor.py index c79d2c0e412..ee5b5beb8af 100644 --- a/source/isaaclab_contrib/test/sensors/test_visuotactile_sensor.py +++ b/source/isaaclab_contrib/test/sensors/test_visuotactile_sensor.py @@ -190,8 +190,7 @@ def teardown(sim): # close all the opened viewport from before. rep.vp_manager.destroy_hydra_textures("Replicator") # stop simulation - # note: cannot use self.sim.stop() since it does one render step after stopping!! This doesn't make sense :( - sim._timeline.stop() + sim.stop() # clear the stage sim.clear_instance() diff --git a/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py b/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py index e5d326e8a4a..7f2bdc9bc94 100644 --- a/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py +++ b/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py @@ -63,8 +63,6 @@ class IsaacEvents(Enum): _PHYSICS_EVENT_TO_ISAAC_EVENT: dict[PhysicsEvent, IsaacEvents] = { PhysicsEvent.MODEL_INIT: IsaacEvents.PHYSICS_WARMUP, PhysicsEvent.PHYSICS_READY: IsaacEvents.PHYSICS_READY, - PhysicsEvent.PRE_STEP: IsaacEvents.PRE_PHYSICS_STEP, - PhysicsEvent.POST_STEP: IsaacEvents.POST_PHYSICS_STEP, PhysicsEvent.STOP: IsaacEvents.TIMELINE_STOP, } @@ -218,8 +216,12 @@ def initialize(cls, sim_context: SimulationContext) -> None: @classmethod def reset(cls, soft: bool = False) -> None: """Reset the physics simulation.""" - if not soft and cls._view is None: - cls._warmup_and_create_views() + if not soft: + # Ensure views are created (warmup only happens once per stage) + if cls._view is None: + cls._warmup_and_create_views() + # Always dispatch PHYSICS_READY on hard reset to initialize newly registered sensors + cls._event_bus.dispatch_event(IsaacEvents.PHYSICS_READY.value, payload={}) device = PhysicsManager._device if "cuda" in device: @@ -615,9 +617,19 @@ def _on_stop(cls, event: Any) -> None: @classmethod def _on_stage_open(cls, event: Any) -> None: - from isaaclab.sim.utils.stage import get_current_stage_id + from isaaclab.sim.utils.stage import get_current_stage, get_current_stage_id + + # Guard against stage open events when stage is not yet valid + stage = get_current_stage() + if stage is None or not stage.GetRootLayer(): + return + + try: + new_stage_id = get_current_stage_id() + except Exception: + # Stage may not be ready for caching yet + return - new_stage_id = get_current_stage_id() if new_stage_id == cls._stage_id: return diff --git a/source/isaaclab_physx/isaaclab_physx/visualizers/ov_visualizer.py b/source/isaaclab_physx/isaaclab_physx/visualizers/ov_visualizer.py index 15f4263bfa1..224a05ad679 100644 --- a/source/isaaclab_physx/isaaclab_physx/visualizers/ov_visualizer.py +++ b/source/isaaclab_physx/isaaclab_physx/visualizers/ov_visualizer.py @@ -9,10 +9,15 @@ import enum import logging +import os from typing import TYPE_CHECKING, Any +import flatdict +import toml + import omni.kit.app +from isaaclab.utils.version import get_isaac_sim_version from isaaclab.visualizers import Visualizer from .ov_visualizer_cfg import OVVisualizerCfg @@ -172,6 +177,9 @@ def initialize(self, scene_data: dict[str, Any] | None = None) -> None: if self._has_gui: self._sim.cfg.enable_scene_query_support = True + # Apply render settings from RenderCfg (including preset loading) + self._apply_render_settings_from_cfg() + # Set initial camera view self.set_camera_view(self.cfg.camera_position, self.cfg.camera_target) @@ -353,6 +361,133 @@ def set_render_mode(self, mode: RenderMode) -> None: raise ValueError(f"Unsupported render mode: {mode}! Please check `RenderMode` for details.") self.render_mode = mode + def _apply_render_settings_from_cfg(self) -> None: # noqa: C901 + """Apply RTX settings from RenderCfg, including loading preset files. + + This method applies rendering settings in the following order: + 1. Load and apply preset settings from rendering mode (performance/balanced/quality) + 2. Apply user-friendly named settings from RenderCfg + 3. Apply arbitrary carb settings from RenderCfg.carb_settings + 4. Apply antialiasing mode if specified + + # THINK(Octi): what if there is no visualizer but rtx camera, this should still be set, should this code + # be add to visualizer at all? We should consider removing this code from visualizer and and to renderer + # implementation once we see how renderer will handle this. + """ + if self._sim is None: + return + + render_cfg = getattr(self._sim.cfg, "render", None) + if render_cfg is None: + return + + # Define mapping of user-friendly RenderCfg names to native carb names + rendering_setting_name_mapping = { + "enable_translucency": "/rtx/translucency/enabled", + "enable_reflections": "/rtx/reflections/enabled", + "enable_global_illumination": "/rtx/indirectDiffuse/enabled", + "enable_dlssg": "/rtx-transient/dlssg/enabled", + "enable_dl_denoiser": "/rtx-transient/dldenoiser/enabled", + "dlss_mode": "/rtx/post/dlss/execMode", + "enable_direct_lighting": "/rtx/directLighting/enabled", + "samples_per_pixel": "/rtx/directLighting/sampledLighting/samplesPerPixel", + "enable_shadows": "/rtx/shadows/enabled", + "enable_ambient_occlusion": "/rtx/ambientOcclusion/enabled", + "dome_light_upper_lower_strategy": "/rtx/domeLight/upperLowerStrategy", + "ambient_light_intensity": "/rtx/sceneDb/ambientLightIntensity", + "ambient_occlusion_denoiser_mode": "/rtx/ambientOcclusion/denoiserMode", + "subpixel_mode": "/rtx/raytracing/subpixel/mode", + "enable_cached_raytracing": "/rtx/raytracing/cached/enabled", + "max_samples_per_launch": "/rtx/pathtracing/maxSamplesPerLaunch", + "view_tile_limit": "/rtx/viewTile/limit", + # RT2 settings + "max_bounces": "/rtx/rtpt/maxBounces", + "split_glass": "/rtx/rtpt/splitGlass", + "split_clearcoat": "/rtx/rtpt/splitClearcoat", + "split_rough_reflection": "/rtx/rtpt/splitRoughReflection", + } + + not_carb_settings = ["rendering_mode", "carb_settings", "antialiasing_mode"] + + # Grab the rendering mode using the following priority: + # 1. Command line argument --rendering_mode, if provided + # 2. rendering_mode from RenderCfg, if set + # 3. Default to "balanced" mode, if neither is specified + rendering_mode = self._sim.get_setting("/isaaclab/rendering/rendering_mode") + if not rendering_mode: + rendering_mode = getattr(render_cfg, "rendering_mode", None) + if not rendering_mode: + rendering_mode = "balanced" + + # Set preset settings (same behavior as the CLI arg --rendering_mode) + if rendering_mode is not None: + # Check if preset is supported + supported_rendering_modes = ["performance", "balanced", "quality"] + if rendering_mode not in supported_rendering_modes: + raise ValueError( + f"RenderCfg rendering mode '{rendering_mode}' not in supported modes {supported_rendering_modes}." + ) + + # Grab Isaac Lab apps path + isaaclab_app_exp_path = os.path.join( + os.path.dirname(os.path.abspath(__file__)), *[".."] * 5, "isaaclab", "apps" + ) + # For Isaac Sim 5.0 compatibility, use the 5.X rendering mode app files in a different folder + if get_isaac_sim_version().major < 6: + isaaclab_app_exp_path = os.path.join(isaaclab_app_exp_path, "isaacsim_5") + + # Grab preset settings + preset_filename = os.path.join(isaaclab_app_exp_path, f"rendering_modes/{rendering_mode}.kit") + if os.path.exists(preset_filename): + with open(preset_filename) as file: + preset_dict = toml.load(file) + preset_dict = dict(flatdict.FlatDict(preset_dict, delimiter=".")) + + # Set presets + for key, value in preset_dict.items(): + key = "/" + key.replace(".", "/") # Convert to carb setting format + self._sim.set_setting(key, value) + else: + logger.warning(f"[OVVisualizer] Preset file not found: {preset_filename}") + + # Set user-friendly named settings + for key, value in vars(render_cfg).items(): + if value is None or key in not_carb_settings: + # Skip unset settings and non-carb settings + continue + if key not in rendering_setting_name_mapping: + # Skip unknown keys (may be custom fields) + continue + carb_key = rendering_setting_name_mapping[key] + self._sim.set_setting(carb_key, value) + + # Set general carb settings + carb_settings = getattr(render_cfg, "carb_settings", None) + if carb_settings is not None: + for key, value in carb_settings.items(): + if "_" in key: + key = "/" + key.replace("_", "/") # Convert from python variable style string + elif "." in key: + key = "/" + key.replace(".", "/") # Convert from .kit file style string + if self._sim.get_setting(key) is None: + raise ValueError(f"'{key}' in RenderCfg.carb_settings does not map to a carb setting.") + self._sim.set_setting(key, value) + + # Set antialiasing mode + antialiasing_mode = getattr(render_cfg, "antialiasing_mode", None) + if antialiasing_mode is not None: + try: + import omni.replicator.core as rep + + rep.settings.set_render_rtx_realtime(antialiasing=antialiasing_mode) + except Exception: + pass + + # WAR: Ensure /rtx/renderMode RaytracedLighting is correctly cased + rendermode = self._sim.get_setting("/rtx/rendermode") + if rendermode is not None and rendermode.lower() == "raytracedlighting": + self._sim.set_setting("/rtx/rendermode", "RaytracedLighting") + def close(self) -> None: """Clean up visualizer resources.""" self._sim = None From d92798e160e72a8748c9ee26a7e01a80a9e6a9ec Mon Sep 17 00:00:00 2001 From: Octi Zhang Date: Sun, 8 Feb 2026 20:28:45 -0800 Subject: [PATCH 26/46] remove redundancy --- source/isaaclab/isaaclab/physics/physics_manager_cfg.py | 7 ------- 1 file changed, 7 deletions(-) diff --git a/source/isaaclab/isaaclab/physics/physics_manager_cfg.py b/source/isaaclab/isaaclab/physics/physics_manager_cfg.py index a39a189ad52..80b00b37e3b 100644 --- a/source/isaaclab/isaaclab/physics/physics_manager_cfg.py +++ b/source/isaaclab/isaaclab/physics/physics_manager_cfg.py @@ -49,10 +49,3 @@ class PhysicsCfg: The material is created at the path: ``{physics_prim_path}/defaultMaterial``. """ - - -# Backward compatibility alias -PhysicsCfg = PhysicsCfg -""".. deprecated:: 2.4 - Use :class:`PhysicsCfg` instead. -""" From b8dbe92c4a0e6b94b96ac0ba77412c1fd6b65dc9 Mon Sep 17 00:00:00 2001 From: Octi Zhang Date: Sun, 8 Feb 2026 21:13:47 -0800 Subject: [PATCH 27/46] added annotation to fix docs --- docs/source/api/lab_physx/isaaclab_physx.assets.rst | 4 ++++ source/isaaclab/isaaclab/actuators/actuator_base_cfg.py | 2 ++ source/isaaclab/isaaclab/app/app_launcher.py | 2 ++ .../isaaclab/assets/articulation/articulation_cfg.py | 2 ++ source/isaaclab/isaaclab/assets/asset_base_cfg.py | 2 ++ .../isaaclab/isaaclab/controllers/differential_ik_cfg.py | 2 ++ source/isaaclab/isaaclab/controllers/joint_impedance.py | 2 ++ .../isaaclab/controllers/operational_space_cfg.py | 2 ++ .../controllers/pink_ik/null_space_posture_task.py | 2 ++ .../isaaclab/isaaclab/controllers/pink_ik/pink_ik_cfg.py | 2 ++ source/isaaclab/isaaclab/devices/device_base.py | 4 +++- source/isaaclab/isaaclab/devices/retargeter_base.py | 6 ++++-- source/isaaclab/isaaclab/devices/teleop_device_factory.py | 2 ++ source/isaaclab/isaaclab/envs/direct_marl_env_cfg.py | 2 ++ source/isaaclab/isaaclab/envs/direct_rl_env_cfg.py | 2 ++ source/isaaclab/isaaclab/envs/manager_based_env.py | 2 ++ source/isaaclab/isaaclab/envs/manager_based_env_cfg.py | 2 ++ source/isaaclab/isaaclab/envs/manager_based_rl_env_cfg.py | 2 ++ source/isaaclab/isaaclab/envs/mdp/actions/actions_cfg.py | 2 ++ .../isaaclab/envs/mdp/actions/rmpflow_actions_cfg.py | 1 + source/isaaclab/isaaclab/envs/mimic_env_cfg.py | 2 ++ source/isaaclab/isaaclab/envs/utils/marl.py | 2 ++ source/isaaclab/isaaclab/scene/interactive_scene.py | 2 ++ source/isaaclab/isaaclab/sensors/camera/camera_cfg.py | 2 ++ .../sensors/frame_transformer/frame_transformer_cfg.py | 2 ++ .../isaaclab/sensors/ray_caster/ray_caster_cfg.py | 2 ++ .../isaaclab/sim/converters/asset_converter_base_cfg.py | 2 ++ .../isaaclab/sim/converters/urdf_converter_cfg.py | 2 ++ source/isaaclab/isaaclab/sim/schemas/schemas_cfg.py | 2 ++ source/isaaclab/isaaclab/sim/simulation_cfg.py | 2 ++ source/isaaclab/isaaclab/sim/simulation_context.py | 8 +++++--- .../isaaclab/isaaclab/sim/spawners/lights/lights_cfg.py | 2 ++ .../sim/spawners/materials/physics_materials_cfg.py | 2 ++ .../sim/spawners/materials/visual_materials_cfg.py | 2 ++ .../isaaclab/isaaclab/sim/spawners/shapes/shapes_cfg.py | 2 ++ source/isaaclab/isaaclab/sim/utils/stage.py | 2 ++ .../isaaclab/isaaclab/ui/xr_widgets/instruction_widget.py | 2 ++ 37 files changed, 81 insertions(+), 6 deletions(-) create mode 100644 docs/source/api/lab_physx/isaaclab_physx.assets.rst diff --git a/docs/source/api/lab_physx/isaaclab_physx.assets.rst b/docs/source/api/lab_physx/isaaclab_physx.assets.rst new file mode 100644 index 00000000000..5234ae1b690 --- /dev/null +++ b/docs/source/api/lab_physx/isaaclab_physx.assets.rst @@ -0,0 +1,4 @@ +isaaclab\_physx.assets +====================== + +.. automodule:: isaaclab_physx.assets diff --git a/source/isaaclab/isaaclab/actuators/actuator_base_cfg.py b/source/isaaclab/isaaclab/actuators/actuator_base_cfg.py index e7a26b52aef..99277f9d613 100644 --- a/source/isaaclab/isaaclab/actuators/actuator_base_cfg.py +++ b/source/isaaclab/isaaclab/actuators/actuator_base_cfg.py @@ -3,6 +3,8 @@ # # SPDX-License-Identifier: BSD-3-Clause +from __future__ import annotations + from dataclasses import MISSING from isaaclab.utils import configclass diff --git a/source/isaaclab/isaaclab/app/app_launcher.py b/source/isaaclab/isaaclab/app/app_launcher.py index ffafa6e26f5..a07897cc0ef 100644 --- a/source/isaaclab/isaaclab/app/app_launcher.py +++ b/source/isaaclab/isaaclab/app/app_launcher.py @@ -12,6 +12,8 @@ :attr:`AppLauncher.app` property. """ +from __future__ import annotations + import argparse import contextlib import logging diff --git a/source/isaaclab/isaaclab/assets/articulation/articulation_cfg.py b/source/isaaclab/isaaclab/assets/articulation/articulation_cfg.py index fad16cd8360..f8c558302d3 100644 --- a/source/isaaclab/isaaclab/assets/articulation/articulation_cfg.py +++ b/source/isaaclab/isaaclab/assets/articulation/articulation_cfg.py @@ -3,6 +3,8 @@ # # SPDX-License-Identifier: BSD-3-Clause +from __future__ import annotations + from dataclasses import MISSING from isaaclab.actuators import ActuatorBaseCfg diff --git a/source/isaaclab/isaaclab/assets/asset_base_cfg.py b/source/isaaclab/isaaclab/assets/asset_base_cfg.py index 9df8e133352..cb24b8f632d 100644 --- a/source/isaaclab/isaaclab/assets/asset_base_cfg.py +++ b/source/isaaclab/isaaclab/assets/asset_base_cfg.py @@ -3,6 +3,8 @@ # # SPDX-License-Identifier: BSD-3-Clause +from __future__ import annotations + from dataclasses import MISSING from typing import Literal diff --git a/source/isaaclab/isaaclab/controllers/differential_ik_cfg.py b/source/isaaclab/isaaclab/controllers/differential_ik_cfg.py index 315a762752c..ce30b131ba7 100644 --- a/source/isaaclab/isaaclab/controllers/differential_ik_cfg.py +++ b/source/isaaclab/isaaclab/controllers/differential_ik_cfg.py @@ -3,6 +3,8 @@ # # SPDX-License-Identifier: BSD-3-Clause +from __future__ import annotations + from dataclasses import MISSING from typing import Literal diff --git a/source/isaaclab/isaaclab/controllers/joint_impedance.py b/source/isaaclab/isaaclab/controllers/joint_impedance.py index bd35089b81a..5baca32385d 100644 --- a/source/isaaclab/isaaclab/controllers/joint_impedance.py +++ b/source/isaaclab/isaaclab/controllers/joint_impedance.py @@ -3,6 +3,8 @@ # # SPDX-License-Identifier: BSD-3-Clause +from __future__ import annotations + from collections.abc import Sequence from dataclasses import MISSING diff --git a/source/isaaclab/isaaclab/controllers/operational_space_cfg.py b/source/isaaclab/isaaclab/controllers/operational_space_cfg.py index d2fc3575bd7..5572ae43925 100644 --- a/source/isaaclab/isaaclab/controllers/operational_space_cfg.py +++ b/source/isaaclab/isaaclab/controllers/operational_space_cfg.py @@ -3,6 +3,8 @@ # # SPDX-License-Identifier: BSD-3-Clause +from __future__ import annotations + from collections.abc import Sequence from dataclasses import MISSING diff --git a/source/isaaclab/isaaclab/controllers/pink_ik/null_space_posture_task.py b/source/isaaclab/isaaclab/controllers/pink_ik/null_space_posture_task.py index 8ab6ddcc2dc..fbd3b84199a 100644 --- a/source/isaaclab/isaaclab/controllers/pink_ik/null_space_posture_task.py +++ b/source/isaaclab/isaaclab/controllers/pink_ik/null_space_posture_task.py @@ -3,6 +3,8 @@ # # SPDX-License-Identifier: BSD-3-Clause +from __future__ import annotations + import numpy as np import pinocchio as pin import scipy.linalg.blas as blas diff --git a/source/isaaclab/isaaclab/controllers/pink_ik/pink_ik_cfg.py b/source/isaaclab/isaaclab/controllers/pink_ik/pink_ik_cfg.py index a66c4aec665..3eb9fa6c575 100644 --- a/source/isaaclab/isaaclab/controllers/pink_ik/pink_ik_cfg.py +++ b/source/isaaclab/isaaclab/controllers/pink_ik/pink_ik_cfg.py @@ -5,6 +5,8 @@ """Configuration for Pink IK controller.""" +from __future__ import annotations + from dataclasses import MISSING from pink.tasks import FrameTask diff --git a/source/isaaclab/isaaclab/devices/device_base.py b/source/isaaclab/isaaclab/devices/device_base.py index a434bcc73cf..edc75797d73 100644 --- a/source/isaaclab/isaaclab/devices/device_base.py +++ b/source/isaaclab/isaaclab/devices/device_base.py @@ -5,6 +5,8 @@ """Base class for teleoperation interface.""" +from __future__ import annotations + from abc import ABC, abstractmethod from collections.abc import Callable from dataclasses import dataclass, field @@ -27,7 +29,7 @@ class DeviceCfg: # Retargeters that transform device data into robot commands retargeters: list[RetargeterCfg] = field(default_factory=list) # Concrete device class to construct for this config. Set by each device module. - class_type: type["DeviceBase"] | None = None + class_type: type[DeviceBase] | None = None @dataclass diff --git a/source/isaaclab/isaaclab/devices/retargeter_base.py b/source/isaaclab/isaaclab/devices/retargeter_base.py index fcd443a155b..77dce9179f6 100644 --- a/source/isaaclab/isaaclab/devices/retargeter_base.py +++ b/source/isaaclab/isaaclab/devices/retargeter_base.py @@ -3,6 +3,8 @@ # # SPDX-License-Identifier: BSD-3-Clause +from __future__ import annotations + from abc import ABC, abstractmethod from dataclasses import dataclass from enum import Enum @@ -15,7 +17,7 @@ class RetargeterCfg: sim_device: str = "cpu" # Concrete retargeter class to construct for this config. Set by each retargeter module. - retargeter_type: type["RetargeterBase"] | None = None + retargeter_type: type[RetargeterBase] | None = None class RetargeterBase(ABC): @@ -56,7 +58,7 @@ def retarget(self, data: Any) -> Any: """ pass - def get_requirements(self) -> list["RetargeterBase.Requirement"]: + def get_requirements(self) -> list[RetargeterBase.Requirement]: """Return the list of required data features for this retargeter. Defaults to requesting all available features for backward compatibility. diff --git a/source/isaaclab/isaaclab/devices/teleop_device_factory.py b/source/isaaclab/isaaclab/devices/teleop_device_factory.py index f7265c41c2c..63de58f975e 100644 --- a/source/isaaclab/isaaclab/devices/teleop_device_factory.py +++ b/source/isaaclab/isaaclab/devices/teleop_device_factory.py @@ -5,6 +5,8 @@ """Factory to create teleoperation devices from configuration.""" +from __future__ import annotations + import inspect import logging from collections.abc import Callable diff --git a/source/isaaclab/isaaclab/envs/direct_marl_env_cfg.py b/source/isaaclab/isaaclab/envs/direct_marl_env_cfg.py index 66b2bcf998d..8fa784ccdf7 100644 --- a/source/isaaclab/isaaclab/envs/direct_marl_env_cfg.py +++ b/source/isaaclab/isaaclab/envs/direct_marl_env_cfg.py @@ -3,6 +3,8 @@ # # SPDX-License-Identifier: BSD-3-Clause +from __future__ import annotations + from dataclasses import MISSING from isaaclab.devices.openxr import XrCfg diff --git a/source/isaaclab/isaaclab/envs/direct_rl_env_cfg.py b/source/isaaclab/isaaclab/envs/direct_rl_env_cfg.py index a1ebb883c65..9158f29fc17 100644 --- a/source/isaaclab/isaaclab/envs/direct_rl_env_cfg.py +++ b/source/isaaclab/isaaclab/envs/direct_rl_env_cfg.py @@ -3,6 +3,8 @@ # # SPDX-License-Identifier: BSD-3-Clause +from __future__ import annotations + from dataclasses import MISSING from isaaclab.devices.openxr import XrCfg diff --git a/source/isaaclab/isaaclab/envs/manager_based_env.py b/source/isaaclab/isaaclab/envs/manager_based_env.py index dc818f3b999..4162b46ad77 100644 --- a/source/isaaclab/isaaclab/envs/manager_based_env.py +++ b/source/isaaclab/isaaclab/envs/manager_based_env.py @@ -3,6 +3,8 @@ # # SPDX-License-Identifier: BSD-3-Clause +from __future__ import annotations + import builtins import logging import warnings diff --git a/source/isaaclab/isaaclab/envs/manager_based_env_cfg.py b/source/isaaclab/isaaclab/envs/manager_based_env_cfg.py index e8f583ddfb3..e9975527d19 100644 --- a/source/isaaclab/isaaclab/envs/manager_based_env_cfg.py +++ b/source/isaaclab/isaaclab/envs/manager_based_env_cfg.py @@ -9,6 +9,8 @@ configuring the environment instances, viewer settings, and simulation parameters. """ +from __future__ import annotations + from dataclasses import MISSING, field import isaaclab.envs.mdp as mdp diff --git a/source/isaaclab/isaaclab/envs/manager_based_rl_env_cfg.py b/source/isaaclab/isaaclab/envs/manager_based_rl_env_cfg.py index eac633e8b99..7fe29ed7003 100644 --- a/source/isaaclab/isaaclab/envs/manager_based_rl_env_cfg.py +++ b/source/isaaclab/isaaclab/envs/manager_based_rl_env_cfg.py @@ -3,6 +3,8 @@ # # SPDX-License-Identifier: BSD-3-Clause +from __future__ import annotations + from dataclasses import MISSING from isaaclab.utils import configclass diff --git a/source/isaaclab/isaaclab/envs/mdp/actions/actions_cfg.py b/source/isaaclab/isaaclab/envs/mdp/actions/actions_cfg.py index 297f8ae9864..bb664445169 100644 --- a/source/isaaclab/isaaclab/envs/mdp/actions/actions_cfg.py +++ b/source/isaaclab/isaaclab/envs/mdp/actions/actions_cfg.py @@ -3,6 +3,8 @@ # # SPDX-License-Identifier: BSD-3-Clause +from __future__ import annotations + from dataclasses import MISSING from isaaclab.controllers import DifferentialIKControllerCfg, OperationalSpaceControllerCfg diff --git a/source/isaaclab/isaaclab/envs/mdp/actions/rmpflow_actions_cfg.py b/source/isaaclab/isaaclab/envs/mdp/actions/rmpflow_actions_cfg.py index 0fbf9d2e889..6bc16f15513 100644 --- a/source/isaaclab/isaaclab/envs/mdp/actions/rmpflow_actions_cfg.py +++ b/source/isaaclab/isaaclab/envs/mdp/actions/rmpflow_actions_cfg.py @@ -3,6 +3,7 @@ # # SPDX-License-Identifier: BSD-3-Clause +from __future__ import annotations from dataclasses import MISSING diff --git a/source/isaaclab/isaaclab/envs/mimic_env_cfg.py b/source/isaaclab/isaaclab/envs/mimic_env_cfg.py index c506df7f20b..a98c34bf5f9 100644 --- a/source/isaaclab/isaaclab/envs/mimic_env_cfg.py +++ b/source/isaaclab/isaaclab/envs/mimic_env_cfg.py @@ -10,6 +10,8 @@ Base MimicEnvCfg object for Isaac Lab Mimic data generation. """ +from __future__ import annotations + import enum from isaaclab.managers.recorder_manager import RecorderManagerBaseCfg diff --git a/source/isaaclab/isaaclab/envs/utils/marl.py b/source/isaaclab/isaaclab/envs/utils/marl.py index 010f6e5e27b..5901bfbc318 100644 --- a/source/isaaclab/isaaclab/envs/utils/marl.py +++ b/source/isaaclab/isaaclab/envs/utils/marl.py @@ -3,6 +3,8 @@ # # SPDX-License-Identifier: BSD-3-Clause +from __future__ import annotations + import math from typing import Any diff --git a/source/isaaclab/isaaclab/scene/interactive_scene.py b/source/isaaclab/isaaclab/scene/interactive_scene.py index 0877411cb53..bfb08ed0407 100644 --- a/source/isaaclab/isaaclab/scene/interactive_scene.py +++ b/source/isaaclab/isaaclab/scene/interactive_scene.py @@ -3,6 +3,8 @@ # # SPDX-License-Identifier: BSD-3-Clause +from __future__ import annotations + import logging from collections.abc import Sequence from typing import Any diff --git a/source/isaaclab/isaaclab/sensors/camera/camera_cfg.py b/source/isaaclab/isaaclab/sensors/camera/camera_cfg.py index ffe2bce7350..a589b0d170e 100644 --- a/source/isaaclab/isaaclab/sensors/camera/camera_cfg.py +++ b/source/isaaclab/isaaclab/sensors/camera/camera_cfg.py @@ -3,6 +3,8 @@ # # SPDX-License-Identifier: BSD-3-Clause +from __future__ import annotations + from dataclasses import MISSING from typing import Literal diff --git a/source/isaaclab/isaaclab/sensors/frame_transformer/frame_transformer_cfg.py b/source/isaaclab/isaaclab/sensors/frame_transformer/frame_transformer_cfg.py index 641bb386354..389f22c505c 100644 --- a/source/isaaclab/isaaclab/sensors/frame_transformer/frame_transformer_cfg.py +++ b/source/isaaclab/isaaclab/sensors/frame_transformer/frame_transformer_cfg.py @@ -3,6 +3,8 @@ # # SPDX-License-Identifier: BSD-3-Clause +from __future__ import annotations + from dataclasses import MISSING from isaaclab.markers.config import FRAME_MARKER_CFG, VisualizationMarkersCfg diff --git a/source/isaaclab/isaaclab/sensors/ray_caster/ray_caster_cfg.py b/source/isaaclab/isaaclab/sensors/ray_caster/ray_caster_cfg.py index ff6872f5970..23981b98ee9 100644 --- a/source/isaaclab/isaaclab/sensors/ray_caster/ray_caster_cfg.py +++ b/source/isaaclab/isaaclab/sensors/ray_caster/ray_caster_cfg.py @@ -5,6 +5,8 @@ """Configuration for the ray-cast sensor.""" +from __future__ import annotations + from dataclasses import MISSING from typing import Literal diff --git a/source/isaaclab/isaaclab/sim/converters/asset_converter_base_cfg.py b/source/isaaclab/isaaclab/sim/converters/asset_converter_base_cfg.py index 79bb8d17d41..3ba2a27c18c 100644 --- a/source/isaaclab/isaaclab/sim/converters/asset_converter_base_cfg.py +++ b/source/isaaclab/isaaclab/sim/converters/asset_converter_base_cfg.py @@ -3,6 +3,8 @@ # # SPDX-License-Identifier: BSD-3-Clause +from __future__ import annotations + from dataclasses import MISSING from isaaclab.utils import configclass diff --git a/source/isaaclab/isaaclab/sim/converters/urdf_converter_cfg.py b/source/isaaclab/isaaclab/sim/converters/urdf_converter_cfg.py index c04ede2400a..6315815b769 100644 --- a/source/isaaclab/isaaclab/sim/converters/urdf_converter_cfg.py +++ b/source/isaaclab/isaaclab/sim/converters/urdf_converter_cfg.py @@ -3,6 +3,8 @@ # # SPDX-License-Identifier: BSD-3-Clause +from __future__ import annotations + from dataclasses import MISSING from typing import Literal diff --git a/source/isaaclab/isaaclab/sim/schemas/schemas_cfg.py b/source/isaaclab/isaaclab/sim/schemas/schemas_cfg.py index 446d7faa105..2086c9d589e 100644 --- a/source/isaaclab/isaaclab/sim/schemas/schemas_cfg.py +++ b/source/isaaclab/isaaclab/sim/schemas/schemas_cfg.py @@ -3,6 +3,8 @@ # # SPDX-License-Identifier: BSD-3-Clause +from __future__ import annotations + from dataclasses import MISSING from typing import Literal diff --git a/source/isaaclab/isaaclab/sim/simulation_cfg.py b/source/isaaclab/isaaclab/sim/simulation_cfg.py index 71bb394f2e8..0f4f810db03 100644 --- a/source/isaaclab/isaaclab/sim/simulation_cfg.py +++ b/source/isaaclab/isaaclab/sim/simulation_cfg.py @@ -9,6 +9,8 @@ configuring the environment instances, viewer settings, and simulation parameters. """ +from __future__ import annotations + import contextlib import warnings from typing import Any, Literal # Literal used by RenderCfg diff --git a/source/isaaclab/isaaclab/sim/simulation_context.py b/source/isaaclab/isaaclab/sim/simulation_context.py index 318976cd6f2..b64b2be3a0a 100644 --- a/source/isaaclab/isaaclab/sim/simulation_context.py +++ b/source/isaaclab/isaaclab/sim/simulation_context.py @@ -3,6 +3,8 @@ # # SPDX-License-Identifier: BSD-3-Clause +from __future__ import annotations + import gc import logging import traceback @@ -30,7 +32,7 @@ class SettingsHelper: """Helper for typed Carbonite settings access.""" - def __init__(self, settings: "carb.settings.ISettings"): + def __init__(self, settings: carb.settings.ISettings): self._settings = settings def set(self, name: str, value: Any) -> None: @@ -67,7 +69,7 @@ class SimulationContext: # SINGLETON PATTERN - _instance: "SimulationContext | None" = None + _instance: SimulationContext | None = None def __new__(cls, cfg: SimulationCfg | None = None): """Enforce singleton pattern.""" @@ -76,7 +78,7 @@ def __new__(cls, cfg: SimulationCfg | None = None): return super().__new__(cls) @classmethod - def instance(cls) -> "SimulationContext | None": + def instance(cls) -> SimulationContext | None: """Get the singleton instance, or None if not created.""" return cls._instance diff --git a/source/isaaclab/isaaclab/sim/spawners/lights/lights_cfg.py b/source/isaaclab/isaaclab/sim/spawners/lights/lights_cfg.py index 60060ea22e5..4768ffcba57 100644 --- a/source/isaaclab/isaaclab/sim/spawners/lights/lights_cfg.py +++ b/source/isaaclab/isaaclab/sim/spawners/lights/lights_cfg.py @@ -3,6 +3,8 @@ # # SPDX-License-Identifier: BSD-3-Clause +from __future__ import annotations + from collections.abc import Callable from dataclasses import MISSING from typing import Literal diff --git a/source/isaaclab/isaaclab/sim/spawners/materials/physics_materials_cfg.py b/source/isaaclab/isaaclab/sim/spawners/materials/physics_materials_cfg.py index ce05c2b9ea4..be63a9dd4a4 100644 --- a/source/isaaclab/isaaclab/sim/spawners/materials/physics_materials_cfg.py +++ b/source/isaaclab/isaaclab/sim/spawners/materials/physics_materials_cfg.py @@ -3,6 +3,8 @@ # # SPDX-License-Identifier: BSD-3-Clause +from __future__ import annotations + from collections.abc import Callable from dataclasses import MISSING from typing import Literal diff --git a/source/isaaclab/isaaclab/sim/spawners/materials/visual_materials_cfg.py b/source/isaaclab/isaaclab/sim/spawners/materials/visual_materials_cfg.py index a0c2874b0e9..09e022c95cb 100644 --- a/source/isaaclab/isaaclab/sim/spawners/materials/visual_materials_cfg.py +++ b/source/isaaclab/isaaclab/sim/spawners/materials/visual_materials_cfg.py @@ -3,6 +3,8 @@ # # SPDX-License-Identifier: BSD-3-Clause +from __future__ import annotations + from collections.abc import Callable from dataclasses import MISSING diff --git a/source/isaaclab/isaaclab/sim/spawners/shapes/shapes_cfg.py b/source/isaaclab/isaaclab/sim/spawners/shapes/shapes_cfg.py index d2de5a7f941..921b1ede29c 100644 --- a/source/isaaclab/isaaclab/sim/spawners/shapes/shapes_cfg.py +++ b/source/isaaclab/isaaclab/sim/spawners/shapes/shapes_cfg.py @@ -3,6 +3,8 @@ # # SPDX-License-Identifier: BSD-3-Clause +from __future__ import annotations + from collections.abc import Callable from dataclasses import MISSING from typing import Literal diff --git a/source/isaaclab/isaaclab/sim/utils/stage.py b/source/isaaclab/isaaclab/sim/utils/stage.py index 3d1f9201a83..c279cec6997 100644 --- a/source/isaaclab/isaaclab/sim/utils/stage.py +++ b/source/isaaclab/isaaclab/sim/utils/stage.py @@ -5,6 +5,8 @@ """Utilities for operating on the USD stage.""" +from __future__ import annotations + import builtins import contextlib import logging diff --git a/source/isaaclab/isaaclab/ui/xr_widgets/instruction_widget.py b/source/isaaclab/isaaclab/ui/xr_widgets/instruction_widget.py index 7d6fe00d7f6..bf5d3e0f31b 100644 --- a/source/isaaclab/isaaclab/ui/xr_widgets/instruction_widget.py +++ b/source/isaaclab/isaaclab/ui/xr_widgets/instruction_widget.py @@ -3,6 +3,8 @@ # # SPDX-License-Identifier: BSD-3-Clause +from __future__ import annotations + import asyncio import functools import textwrap From a8e1dc0b6e6addce2e5a5586069832fd1a4e268a Mon Sep 17 00:00:00 2001 From: Matthew Trepte Date: Thu, 22 Jan 2026 19:51:58 +0000 Subject: [PATCH 28/46] initial work on omni physx compat newton-based viewers --- source/isaaclab/isaaclab/app/app_launcher.py | 59 +++++++++ .../isaaclab/isaaclab/sim/simulation_cfg.py | 14 ++- .../isaaclab/sim/simulation_context.py | 116 +++++++++++++----- source/isaaclab/isaaclab/utils/__init__.py | 1 + source/isaaclab/setup.py | 8 +- 5 files changed, 166 insertions(+), 32 deletions(-) diff --git a/source/isaaclab/isaaclab/app/app_launcher.py b/source/isaaclab/isaaclab/app/app_launcher.py index a07897cc0ef..a9ac07fbfb8 100644 --- a/source/isaaclab/isaaclab/app/app_launcher.py +++ b/source/isaaclab/isaaclab/app/app_launcher.py @@ -117,6 +117,7 @@ def __init__(self, launcher_args: argparse.Namespace | dict | None = None, **kwa self._livestream: Literal[0, 1, 2] # 0: Disabled, 1: WebRTC public, 2: WebRTC private self._offscreen_render: bool # 0: Disabled, 1: Enabled self._sim_experience_file: str # Experience file to load + self._visualizer: list[str] | None # Visualizer backends to use # Exposed to train scripts self.device_id: int # device ID for GPU simulation (defaults to 0) @@ -306,6 +307,16 @@ def add_app_launcher_args(parser: argparse.ArgumentParser) -> None: default=AppLauncher._APPLAUNCHER_CFG_INFO["device"][1], help='The device to run the simulation on. Can be "cpu", "cuda", "cuda:N", where N is the device ID', ) + arg_group.add_argument( + "--visualizer", + type=str, + nargs="+", + default=None, + help=( + "Visualizer backend(s) to use. Valid values: newton, rerun, omniverse." + " Multiple visualizers can be specified: --visualizer rerun newton" + ), + ) # Add the deprecated cpu flag to raise an error if it is used arg_group.add_argument("--cpu", action="store_true", help=argparse.SUPPRESS) arg_group.add_argument( @@ -391,6 +402,7 @@ def add_app_launcher_args(parser: argparse.ArgumentParser) -> None: "device": ([str], "cuda:0"), "experience": ([str], ""), "rendering_mode": ([str], "balanced"), + "visualizer": ([list, type(None)], None), } """A dictionary of arguments added manually by the :meth:`AppLauncher.add_app_launcher_args` method. @@ -490,6 +502,7 @@ def _config_resolution(self, launcher_args: dict): self._resolve_headless_settings(launcher_args, livestream_arg, livestream_env) self._resolve_camera_settings(launcher_args) self._resolve_xr_settings(launcher_args) + self._resolve_visualizer_settings(launcher_args) self._resolve_viewport_settings(launcher_args) # Handle device and distributed settings @@ -775,6 +788,46 @@ def _resolve_anim_recording_settings(self, launcher_args: dict): raise ValueError("Animation recording is not supported in headless mode.") sys.argv += ["--enable", "omni.physx.pvd"] + def _resolve_visualizer_settings(self, launcher_args: dict) -> None: + """Resolve visualizer related settings.""" + visualizers = launcher_args.pop("visualizer", AppLauncher._APPLAUNCHER_CFG_INFO["visualizer"][1]) + valid_visualizers = {"newton", "rerun", "omniverse"} + if visualizers is not None and len(visualizers) > 0: + invalid = [v for v in visualizers if v not in valid_visualizers] + if invalid: + raise ValueError( + f"Invalid visualizer(s) specified: {invalid}. Valid options are: {sorted(valid_visualizers)}" + ) + self._visualizer = visualizers if visualizers and len(visualizers) > 0 else None + + # Auto-adjust headless based on requested visualizers (parity with feature/newton behavior). + if self._visualizer is None: + if not self._headless and self._livestream not in {1, 2}: + self._headless = True + launcher_args["headless"] = True + print( + "[INFO][AppLauncher]: No visualizers specified. " + "Automatically enabling headless mode. Use --visualizer to enable GUI." + ) + return + + if "omniverse" in self._visualizer: + if self._headless: + self._headless = False + launcher_args["headless"] = False + print( + "[INFO][AppLauncher]: Omniverse visualizer requested. " + "Forcing headless=False for GUI." + ) + else: + if not self._headless and self._livestream not in {1, 2}: + self._headless = True + launcher_args["headless"] = True + print( + f"[INFO][AppLauncher]: Visualizer(s) {self._visualizer} requested. " + "Enabling headless mode for SimulationApp (visualizers run independently)." + ) + def _resolve_kit_args(self, launcher_args: dict): """Resolve additional arguments passed to Kit.""" # Resolve additional arguments passed to Kit @@ -865,6 +918,12 @@ def _load_extensions(self): # for example: the `Camera` sensor class carb_settings_iface.set_bool("/isaaclab/render/rtx_sensors", False) + # store visualizer selection for SimulationContext + if self._visualizer is not None: + carb_settings_iface.set_string("/isaaclab/visualizer", ",".join(self._visualizer)) + else: + carb_settings_iface.set_string("/isaaclab/visualizer", "") + # set fabric update flag to disable updating transforms when rendering is disabled carb_settings_iface.set_bool("/physics/fabricUpdateTransformations", self._rendering_enabled()) diff --git a/source/isaaclab/isaaclab/sim/simulation_cfg.py b/source/isaaclab/isaaclab/sim/simulation_cfg.py index 0f4f810db03..ae9bd5e51ea 100644 --- a/source/isaaclab/isaaclab/sim/simulation_cfg.py +++ b/source/isaaclab/isaaclab/sim/simulation_cfg.py @@ -232,6 +232,9 @@ class SimulationCfg: a different config (e.g., NewtonManagerCfg) to use a different physics backend. """ + physics_backend: Literal["omni", "newton"] = "omni" + """Physics backend to use for scene data providers and visualizers.""" + render: RenderCfg = RenderCfg() """Render settings. Default is RenderCfg().""" @@ -255,7 +258,16 @@ class SimulationCfg: """ visualizer_cfgs: list[VisualizerCfg] | VisualizerCfg | None = None - """The list of visualizer configurations. Default is None.""" + """Visualizer settings. Default is no visualizer. + + Visualizers are separate from Renderers and intended for light-weight monitoring and debugging. + + This field can support multiple visualizer backends. It accepts: + + * A single VisualizerCfg: One visualizer will be created + * A list of VisualizerCfg: Multiple visualizers will be created + * None or empty list: No visualizers will be created + """ # Deprecated fields - accepted in constructor for backward compatibility dt: float | None = None diff --git a/source/isaaclab/isaaclab/sim/simulation_context.py b/source/isaaclab/isaaclab/sim/simulation_context.py index b64b2be3a0a..96c4896db3b 100644 --- a/source/isaaclab/isaaclab/sim/simulation_context.py +++ b/source/isaaclab/isaaclab/sim/simulation_context.py @@ -21,8 +21,9 @@ import isaaclab.sim.utils.stage as stage_utils from isaaclab.physics import PhysicsManager from isaaclab.sim.utils import create_new_stage_in_memory -from isaaclab.visualizers import Visualizer +from isaaclab.visualizers import NewtonVisualizerCfg, OVVisualizerCfg, RerunVisualizerCfg, Visualizer +from .scene_data_providers import SceneDataProvider from .simulation_cfg import SimulationCfg from .spawners import DomeLightCfg, GroundPlaneCfg @@ -122,7 +123,8 @@ def __init__(self, cfg: SimulationCfg | None = None): self.physics_manager: type[PhysicsManager] = self._physics.class_type self.physics_manager.initialize(self) - # Initialize visualizers + # Initialize visualizers and scene data provider + self._scene_data_provider: SceneDataProvider | None = None self._init_visualizers() # Cache commonly-used settings (these don't change during runtime) @@ -202,40 +204,87 @@ def get_physics_dt(self) -> float: return self.physics_manager.get_physics_dt() # VISUALIZER MANAGEMENT + def set_scene_info(self, scene: Any) -> None: + """Set scene info (num_envs, env_origins) from an InteractiveScene-like object.""" + if scene is None: + return + + num_envs = getattr(scene, "num_envs", None) + if num_envs is not None: + self._num_envs = num_envs + if self._scene_data_provider is not None: + set_num_envs = getattr(self._scene_data_provider, "set_num_envs", None) + if callable(set_num_envs): + set_num_envs(num_envs) + + env_origins = getattr(scene, "env_origins", None) + if env_origins is not None: + self._env_origins = env_origins + if self._scene_data_provider is not None: + set_env_origins = getattr(self._scene_data_provider, "set_env_origins", None) + if callable(set_env_origins): + set_env_origins(env_origins) + + def _create_default_visualizer_configs(self, requested_visualizers: list[str]) -> list: + """Create default visualizer configs for requested types.""" + default_configs = [] + for viz_type in requested_visualizers: + try: + if viz_type == "newton": + default_configs.append(NewtonVisualizerCfg()) + elif viz_type == "rerun": + default_configs.append(RerunVisualizerCfg()) + elif viz_type == "omniverse": + default_configs.append(OVVisualizerCfg()) + else: + logger.warning( + f"[SimulationContext] Unknown visualizer type '{viz_type}' requested. " + "Valid types: 'newton', 'rerun', 'omniverse'. Skipping." + ) + except Exception as exc: + logger.error(f"[SimulationContext] Failed to create default config for visualizer '{viz_type}': {exc}") + return default_configs + def _init_visualizers(self) -> None: """Initialize visualizers based on config and settings.""" self._visualizers: list[Visualizer] = [] self._viz_dt = self.cfg.physics.dt * self.cfg.render_interval - # Determine which visualizers to create - viz_str = "omniverse" # Default - requested = [v.strip() for v in viz_str.split(",") if v.strip()] - - if len(requested) > 0: - # Get or create visualizer configs - cfg_list = self.cfg.visualizer_cfgs - from isaaclab_physx.visualizers import OVVisualizerCfg - - type_map = {"omniverse": OVVisualizerCfg} - viz_cfgs = [] - if cfg_list is None: - for viz_type in requested: - viz_cfgs.append(type_map[viz_type]()) + visualizer_cfgs: list = [] + if self.cfg.visualizer_cfgs is not None: + visualizer_cfgs = self.cfg.visualizer_cfgs if isinstance(self.cfg.visualizer_cfgs, list) else [ + self.cfg.visualizer_cfgs + ] + + if len(visualizer_cfgs) == 0: + requested_visualizers_str = self.get_setting("/isaaclab/visualizer") + if requested_visualizers_str: + requested_visualizers = [v.strip() for v in requested_visualizers_str.split(",") if v.strip()] + visualizer_cfgs = self._create_default_visualizer_configs(requested_visualizers) else: - viz_cfgs = cfg_list if isinstance(cfg_list, list) else [cfg_list] - - # Create and initialize each visualizer - for cfg in viz_cfgs: - self._visualizers.append(cfg.create_visualizer()) - # build scene data for visualizer initialization - if cfg.visualizer_type in ("newton", "rerun"): - scene_data = {"scene_data_provider": None} - elif cfg.visualizer_type == "omniverse": - scene_data = {"usd_stage": self.stage, "simulation_context": self} - else: - scene_data = {} - self._visualizers[-1].initialize(scene_data) - logger.info(f"Initialized visualizer: {type(self._visualizers[-1]).__name__}") + return + + self._scene_data_provider = SceneDataProvider( + backend=self.cfg.physics_backend, + visualizer_cfgs=visualizer_cfgs, + stage=self.stage, + simulation_context=self, + ) + + # Create and initialize each visualizer + for cfg in visualizer_cfgs: + try: + visualizer = cfg.create_visualizer() + scene_data: dict[str, Any] = {"scene_data_provider": self._scene_data_provider} + if cfg.visualizer_type == "omniverse": + scene_data["usd_stage"] = self.stage + scene_data["simulation_context"] = self + + visualizer.initialize(scene_data) + self._visualizers.append(visualizer) + logger.info(f"Initialized visualizer: {type(visualizer).__name__} (type: {cfg.visualizer_type})") + except Exception as exc: + logger.error(f"Failed to initialize visualizer '{cfg.visualizer_type}' ({type(cfg).__name__}): {exc}") @property def visualizers(self) -> list[Visualizer]: @@ -282,6 +331,8 @@ def step(self, render: bool = True) -> None: def render(self, mode: int | None = None) -> None: """Render the scene via all active visualizers.""" self.physics_manager.forward() + if self._scene_data_provider: + self._scene_data_provider.update() for viz in self._visualizers: if not viz.is_rendering_paused() and viz.is_running(): viz.step(self.get_rendering_dt(), state=None) @@ -344,6 +395,11 @@ def clear_instance(cls) -> None: for viz in cls._instance._visualizers: viz.close() cls._instance._visualizers.clear() + if cls._instance._scene_data_provider is not None: + close_provider = getattr(cls._instance._scene_data_provider, "close", None) + if callable(close_provider): + close_provider() + cls._instance._scene_data_provider = None # Remove stage from cache stage_cache = UsdUtils.StageCache.Get() diff --git a/source/isaaclab/isaaclab/utils/__init__.py b/source/isaaclab/isaaclab/utils/__init__.py index 1295715857f..5dc6e92da58 100644 --- a/source/isaaclab/isaaclab/utils/__init__.py +++ b/source/isaaclab/isaaclab/utils/__init__.py @@ -13,6 +13,7 @@ from .logger import * from .mesh import * from .modifiers import * +from .simulation_runner import close_simulation, is_simulation_running from .string import * from .timer import Timer from .types import * diff --git a/source/isaaclab/setup.py b/source/isaaclab/setup.py index 360b9771f98..7ad8cd8ce24 100644 --- a/source/isaaclab/setup.py +++ b/source/isaaclab/setup.py @@ -33,7 +33,13 @@ # image processing "transformers==4.57.6", "einops", # needed for transformers, doesn't always auto-install - "warp-lang", + "warp-lang==1.11.0.dev20251205", + # newton visualizers / backend dependencies + "mujoco>=3.4.0.dev839962392", + "mujoco-warp@ git+https://github.com/google-deepmind/mujoco_warp.git@e9a67538f2c14486121635074c5a5fd6ca55fa83", + "newton@ git+https://github.com/newton-physics/newton.git@beta-0.2.1", + "imgui-bundle==1.92.0", + "PyOpenGL-accelerate==3.1.10", "matplotlib>=3.10.3", # minimum version for Python 3.12 support # make sure this is consistent with isaac sim version "pillow==12.0.0", From d93b6de11043c61eff67049025a83a364ab48ed1 Mon Sep 17 00:00:00 2001 From: Matthew Trepte Date: Sat, 24 Jan 2026 03:22:48 +0000 Subject: [PATCH 29/46] testing --- .../isaaclab/envs/manager_based_env.py | 8 + .../isaaclab/scene/interactive_scene.py | 21 + .../sim/scene_data_providers/__init__.py | 18 + .../newton_scene_data_provider.py | 99 +++ .../ov_scene_data_provider.py | 571 ++++++++++++++++++ .../scene_data_provider.py | 124 ++++ .../spawners/materials/visual_materials.py | 30 +- .../isaaclab/utils/simulation_runner.py | 37 ++ .../isaaclab/isaaclab/visualizers/__init__.py | 61 +- .../isaaclab/visualizers/newton_visualizer.py | 333 ++++++++++ .../visualizers/newton_visualizer_cfg.py | 57 ++ .../isaaclab/visualizers/ov_visualizer.py | 276 +++++++++ .../isaaclab/visualizers/ov_visualizer_cfg.py | 33 + .../isaaclab/visualizers/rerun_visualizer.py | 225 +++++++ .../visualizers/rerun_visualizer_cfg.py | 35 ++ .../isaaclab/visualizers/visualizer.py | 13 +- .../isaaclab/visualizers/visualizer_cfg.py | 8 +- 17 files changed, 1907 insertions(+), 42 deletions(-) create mode 100644 source/isaaclab/isaaclab/sim/scene_data_providers/__init__.py create mode 100644 source/isaaclab/isaaclab/sim/scene_data_providers/newton_scene_data_provider.py create mode 100644 source/isaaclab/isaaclab/sim/scene_data_providers/ov_scene_data_provider.py create mode 100644 source/isaaclab/isaaclab/sim/scene_data_providers/scene_data_provider.py create mode 100644 source/isaaclab/isaaclab/utils/simulation_runner.py create mode 100644 source/isaaclab/isaaclab/visualizers/newton_visualizer.py create mode 100644 source/isaaclab/isaaclab/visualizers/newton_visualizer_cfg.py create mode 100644 source/isaaclab/isaaclab/visualizers/ov_visualizer.py create mode 100644 source/isaaclab/isaaclab/visualizers/ov_visualizer_cfg.py create mode 100644 source/isaaclab/isaaclab/visualizers/rerun_visualizer.py create mode 100644 source/isaaclab/isaaclab/visualizers/rerun_visualizer_cfg.py diff --git a/source/isaaclab/isaaclab/envs/manager_based_env.py b/source/isaaclab/isaaclab/envs/manager_based_env.py index 4162b46ad77..4bb9999b4ee 100644 --- a/source/isaaclab/isaaclab/envs/manager_based_env.py +++ b/source/isaaclab/isaaclab/envs/manager_based_env.py @@ -140,6 +140,14 @@ def __init__(self, cfg: ManagerBasedEnvCfg): self.scene = InteractiveScene(self.cfg.scene) attach_stage_to_usd_context() print("[INFO]: Scene manager: ", self.scene) + from isaaclab.sim.utils import find_matching_prim_paths + + env_prim_paths = find_matching_prim_paths("/World/envs/env_.*", stage=self.scene.stage) + print( + "[SceneDebug] env prims after InteractiveScene: " + f"num_envs_setting={self.cfg.scene.num_envs}, env_prims={len(env_prim_paths)}" + ) + import ipdb; ipdb.set_trace() # set up camera viewport controller # viewport is not available in other rendering modes so the function will throw a warning diff --git a/source/isaaclab/isaaclab/scene/interactive_scene.py b/source/isaaclab/isaaclab/scene/interactive_scene.py index bfb08ed0407..20713c0f15e 100644 --- a/source/isaaclab/isaaclab/scene/interactive_scene.py +++ b/source/isaaclab/isaaclab/scene/interactive_scene.py @@ -123,6 +123,10 @@ def __init__(self, cfg: InteractiveSceneCfg): cfg.validate() # store inputs self.cfg = cfg + + # TODO(mtrepte): remove + # self.cfg.clone_in_fabric = False + # initialize scene elements self._terrain = None self._articulations = dict() @@ -136,6 +140,11 @@ def __init__(self, cfg: InteractiveSceneCfg): self.sim = SimulationContext.instance() self.stage = get_current_stage() self.stage_id = get_current_stage_id() + # publish num_envs for consumers outside the scene + try: + self.sim.set_setting("/isaaclab/scene/num_envs", int(self.cfg.num_envs)) + except Exception: + pass # physics scene path self._physics_scene_path = None # prepare cloner for environment replication @@ -273,6 +282,18 @@ def clone_environments(self, copy_from_source: bool = False): if self._default_env_origins is None: self._default_env_origins = torch.tensor(env_origins, device=self.device, dtype=torch.float32) + # publish env origins for consumers that cannot read USD (e.g., Fabric clones) + try: + if hasattr(env_origins, "flatten"): + origins_list = env_origins.flatten().tolist() + else: + origins_list = [] + for origin in env_origins: + origins_list.extend(list(origin)) + self.sim.set_setting("/isaaclab/scene/env_origins", origins_list) + except Exception: + pass + def filter_collisions(self, global_prim_paths: list[str] | None = None): """Filter environments collisions. diff --git a/source/isaaclab/isaaclab/sim/scene_data_providers/__init__.py b/source/isaaclab/isaaclab/sim/scene_data_providers/__init__.py new file mode 100644 index 00000000000..55ccb14863c --- /dev/null +++ b/source/isaaclab/isaaclab/sim/scene_data_providers/__init__.py @@ -0,0 +1,18 @@ +#!/usr/bin/env python3 +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Scene data providers for visualizers and renderers.""" + +from .scene_data_provider import SceneDataProvider, SceneDataProviderBase +from .newton_scene_data_provider import NewtonSceneDataProvider +from .ov_scene_data_provider import OmniSceneDataProvider + +__all__ = [ + "SceneDataProvider", + "SceneDataProviderBase", + "NewtonSceneDataProvider", + "OmniSceneDataProvider", +] diff --git a/source/isaaclab/isaaclab/sim/scene_data_providers/newton_scene_data_provider.py b/source/isaaclab/isaaclab/sim/scene_data_providers/newton_scene_data_provider.py new file mode 100644 index 00000000000..d664abbe343 --- /dev/null +++ b/source/isaaclab/isaaclab/sim/scene_data_providers/newton_scene_data_provider.py @@ -0,0 +1,99 @@ +#!/usr/bin/env python3 +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Newton-backed scene data provider.""" + +from __future__ import annotations + +import logging +from typing import Any + +from .scene_data_provider import SceneDataProviderBase + +logger = logging.getLogger(__name__) + + +class NewtonSceneDataProvider(SceneDataProviderBase): + """Newton-backed scene data provider (when Newton physics is the active backend).""" + + def __init__(self, visualizer_cfgs: list[Any] | None) -> None: + self._has_newton_visualizer = False + self._has_rerun_visualizer = False + self._has_ov_visualizer = False + self._metadata: dict[str, Any] = {} + + if visualizer_cfgs: + for cfg in visualizer_cfgs: + viz_type = getattr(cfg, "visualizer_type", None) + if viz_type == "newton": + self._has_newton_visualizer = True + elif viz_type == "rerun": + self._has_rerun_visualizer = True + elif viz_type == "omniverse": + self._has_ov_visualizer = True + + # Lazy import to keep develop usable without Newton installed. + try: + from isaaclab.sim._impl.newton_manager import NewtonManager + + self._metadata = { + "physics_backend": "newton", + "num_envs": NewtonManager._num_envs if NewtonManager._num_envs is not None else 0, + "gravity_vector": NewtonManager._gravity_vector, + "clone_physics_only": NewtonManager._clone_physics_only, + } + except Exception: + self._metadata = {"physics_backend": "newton"} + + def update(self) -> None: + return None + + def get_model(self): + if not (self._has_newton_visualizer or self._has_rerun_visualizer): + return None + try: + from isaaclab.sim._impl.newton_manager import NewtonManager + + return NewtonManager._model + except Exception: + return None + + def get_state(self): + if not (self._has_newton_visualizer or self._has_rerun_visualizer): + return None + try: + from isaaclab.sim._impl.newton_manager import NewtonManager + + return NewtonManager._state_0 + except Exception: + return None + + def get_metadata(self) -> dict[str, Any]: + return dict(self._metadata) + + def get_transforms(self) -> dict[str, Any] | None: + return None + + def get_velocities(self) -> dict[str, Any] | None: + try: + from isaaclab.sim._impl.newton_manager import NewtonManager + + state = NewtonManager._state_0 + if state is None: + return None + return {"body_qd": state.body_qd} + except Exception: + return None + + def get_contacts(self) -> dict[str, Any] | None: + try: + from isaaclab.sim._impl.newton_manager import NewtonManager + + if NewtonManager._contacts is None: + return None + return {"contacts": NewtonManager._contacts} + except Exception: + return None diff --git a/source/isaaclab/isaaclab/sim/scene_data_providers/ov_scene_data_provider.py b/source/isaaclab/isaaclab/sim/scene_data_providers/ov_scene_data_provider.py new file mode 100644 index 00000000000..52e5afd0fd9 --- /dev/null +++ b/source/isaaclab/isaaclab/sim/scene_data_providers/ov_scene_data_provider.py @@ -0,0 +1,571 @@ +#!/usr/bin/env python3 +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Omni PhysX-backed scene data provider.""" + +from __future__ import annotations + +import logging +import re +from typing import Any + +from .scene_data_provider import SceneDataProviderBase + +logger = logging.getLogger(__name__) + + +class OmniSceneDataProvider(SceneDataProviderBase): + """Omni PhysX-backed scene data provider. + + This provider can generate a Newton-compatible Model/State for use by Newton and Rerun + visualizers while the active physics backend is Omni PhysX. + """ + + def __init__(self, visualizer_cfgs: list[Any] | None, stage, simulation_context) -> None: + from isaacsim.core.simulation_manager import SimulationManager + from pxr import UsdGeom + + self._stage = stage + self._simulation_context = simulation_context + self._physics_sim_view = SimulationManager.get_physics_sim_view() + self._rigid_body_view = None + self._articulation_view = None + self._contact_view = None + self._xform_views: dict[str, Any] = {} + self._body_key_index_map: dict[str, int] = {} + self._view_body_index_map: dict[str, list[int]] = {} + + self._has_newton_visualizer = False + self._has_rerun_visualizer = False + self._has_ov_visualizer = False + if visualizer_cfgs: + for cfg in visualizer_cfgs: + viz_type = getattr(cfg, "visualizer_type", None) + if viz_type == "newton": + self._has_newton_visualizer = True + elif viz_type == "rerun": + self._has_rerun_visualizer = True + elif viz_type == "omniverse": + self._has_ov_visualizer = True + + self._metadata = { + "physics_backend": "omni", + "num_envs": self._get_num_envs(), + "gravity_vector": tuple(self._simulation_context.cfg.gravity), + "clone_physics_only": False, + } + + self._device = getattr(self._simulation_context, "device", "cuda:0") + self._newton_model = None + self._newton_state = None + self._rigid_body_paths: list[str] = [] + self._set_body_q_kernel = None + self._up_axis = UsdGeom.GetStageUpAxis(self._stage) + + if self._has_newton_visualizer or self._has_rerun_visualizer: + self._build_newton_model_from_usd() + self._setup_rigid_body_view() + self._setup_articulation_view() + + def _get_num_envs(self) -> int: + try: + import carb + + carb_settings_iface = carb.settings.get_settings() + num_envs = carb_settings_iface.get("/isaaclab/scene/num_envs") + if num_envs: + return int(num_envs) + except Exception: + return 0 + return 0 + + @staticmethod + def _wildcard_env_paths(paths: list[str]) -> list[str]: + wildcard_paths = [] + for path in paths: + if "/World/envs/env_0" in path: + wildcard_paths.append(path.replace("/World/envs/env_0", "/World/envs/env_*")) + return list(dict.fromkeys(wildcard_paths)) if wildcard_paths else paths + + def _refresh_newton_model_if_needed(self) -> None: + num_envs = self._get_num_envs() + if num_envs <= 0: + return + + if self._newton_model is None or self._newton_state is None: + self._build_newton_model_from_usd() + self._setup_rigid_body_view() + self._setup_articulation_view() + return + + if self._metadata.get("num_envs", 0) != num_envs: + self._build_newton_model_from_usd() + self._setup_rigid_body_view() + self._setup_articulation_view() + return + + def _build_newton_model_from_usd(self) -> None: + # TODO(mtrepte): add support for fabric cloning + try: + from newton import ModelBuilder + from isaaclab.sim.utils import find_matching_prim_paths + + num_envs = self._get_num_envs() + + import ipdb; ipdb.set_trace() + env_prim_paths = find_matching_prim_paths("/World/envs/env_.*", stage=self._stage) + print( + "[SceneDataProvider] Stage env prims before add_usd: "+ + f"num_envs_setting={num_envs}, env_prims={len(env_prim_paths)}" + ) + + builder = ModelBuilder(up_axis=self._up_axis) + builder.add_usd(self._stage) + + self._newton_model = builder.finalize(device=self._device) + self._metadata["num_envs"] = num_envs + self._newton_model.num_envs = self._metadata.get("num_envs", 0) + self._newton_state = self._newton_model.state() + self._rigid_body_paths = list(self._newton_model.body_key) + self._xform_views.clear() + self._contact_view = None + self._body_key_index_map = {path: i for i, path in enumerate(self._rigid_body_paths)} + self._view_body_index_map = {} + except ModuleNotFoundError as exc: + logger.error( + "[SceneDataProvider] Newton module not available. " + "Install the Newton backend to use newton/rerun visualizers." + ) + logger.debug(f"[SceneDataProvider] Newton import error: {exc}") + except Exception as exc: + logger.error(f"[SceneDataProvider] Failed to build Newton model from USD: {exc}") + self._newton_model = None + self._newton_state = None + self._rigid_body_paths = [] + + def _setup_rigid_body_view(self) -> None: + if not self._rigid_body_paths: + return + try: + paths_to_use = self._wildcard_env_paths(list(self._rigid_body_paths)) + self._rigid_body_view = self._physics_sim_view.create_rigid_body_view(paths_to_use) + self._cache_view_index_map(self._rigid_body_view, "rigid_body_view") + except Exception as exc: + logger.warning(f"[SceneDataProvider] Failed to create RigidBodyView: {exc}") + self._rigid_body_view = None + + def _setup_articulation_view(self) -> None: + try: + from pxr import UsdPhysics + + from isaaclab.sim.utils import get_all_matching_child_prims + + root_prims = get_all_matching_child_prims( + "/World", + predicate=lambda prim: prim.HasAPI(UsdPhysics.ArticulationRootAPI), + stage=self._stage, + traverse_instance_prims=True, + ) + if not root_prims: + return + + paths_to_use = self._wildcard_env_paths([prim.GetPath().pathString for prim in root_prims]) + exprs = [path.replace(".*", "*") for path in paths_to_use] + self._articulation_view = self._physics_sim_view.create_articulation_view( + exprs if len(exprs) > 1 else exprs[0] + ) + self._cache_view_index_map(self._articulation_view, "articulation_view") + except Exception as exc: + logger.warning(f"[SceneDataProvider] Failed to create ArticulationView: {exc}") + self._articulation_view = None + + def _get_view_world_poses(self, view): + if view is None: + return None, None + + method_names = ( + "get_world_poses", + "get_world_transforms", + "get_transforms", + "get_poses", + ) + + for name in method_names: + method = getattr(view, name, None) + if method is None: + continue + try: + result = method() + except Exception: + continue + + if isinstance(result, tuple) and len(result) == 2: + return result + + try: + if hasattr(result, "shape") and result.shape[-1] == 7: + positions = result[..., :3] + orientations = result[..., 3:7] + return positions, orientations + except Exception: + continue + + return None, None + + def _cache_view_index_map(self, view, key: str) -> None: + prim_paths = getattr(view, "prim_paths", None) + if not prim_paths or not self._rigid_body_paths: + return + + def split_env(path: str) -> tuple[int | None, str]: + match = re.search(r"/World/envs/env_(\d+)(/.*)", path) + return (int(match.group(1)), match.group(2)) if match else (None, path) + + view_map: dict[tuple[int | None, str], int] = {} + for view_idx, path in enumerate(prim_paths): + env_id, rel = split_env(path) + view_map[(env_id, rel)] = view_idx + + order: list[int | None] = [None] * len(self._rigid_body_paths) + for body_idx, path in enumerate(self._rigid_body_paths): + env_id, rel = split_env(path) + view_idx = view_map.get((env_id, rel)) + if view_idx is None: + view_idx = view_map.get((None, rel)) + order[body_idx] = view_idx + + if all(idx is not None for idx in order): + self._view_body_index_map[key] = order # type: ignore[arg-type] + + def _get_view_velocities(self, view): + if view is None: + return None, None + + # Preferred: combined velocities + method = getattr(view, "get_velocities", None) + if method is not None: + try: + result = method() + if isinstance(result, tuple) and len(result) == 2: + return result + if hasattr(result, "shape") and result.shape[-1] == 6: + return result[..., :3], result[..., 3:6] + except Exception: + pass + + # Fallback: split linear/angular + get_linear = getattr(view, "get_linear_velocities", None) + get_angular = getattr(view, "get_angular_velocities", None) + if get_linear is not None and get_angular is not None: + try: + return get_linear(), get_angular() + except Exception: + return None, None + + return None, None + + def _setup_contact_view(self) -> None: + if not self._rigid_body_paths or self._contact_view is not None: + return + try: + from pxr import PhysxSchema + + contact_paths = [ + path + for path in self._rigid_body_paths + if self._stage.GetPrimAtPath(path).HasAPI(PhysxSchema.PhysxContactReportAPI) + ] + if contact_paths: + contact_paths = self._wildcard_env_paths(contact_paths) + self._contact_view = self._physics_sim_view.create_rigid_contact_view(contact_paths) + except Exception as exc: + logger.debug(f"[SceneDataProvider] Failed to create ContactView: {exc}") + self._contact_view = None + + def _get_view_contacts(self, view): + if view is None: + return None + dt = getattr(self._simulation_context, "cfg", None) + dt = getattr(dt, "dt", 1.0 / 60.0) if dt is not None else 1.0 / 60.0 + + try: + num_envs = int(self._metadata.get("num_envs") or 1) + view_count = getattr(view, "count", 0) + num_bodies = view_count // num_envs if num_envs > 0 and view_count else 0 + num_filters = getattr(view, "filter_count", 0) + + output: dict[str, Any] = {} + + method = getattr(view, "get_net_contact_forces", None) + if method is not None: + output["net_forces_w"] = method(dt=dt) + + method = getattr(view, "get_contact_data", None) + if method is not None: + data = method(dt=dt) + if isinstance(data, tuple) and len(data) >= 6: + _, contact_points, contact_normals, contact_distances, buffer_count, buffer_start_indices = data[:6] + if num_envs > 0 and num_bodies > 0 and num_filters > 0: + output["contact_points_w"] = self._unpack_contact_buffer_data( + contact_points, + buffer_count, + buffer_start_indices, + num_envs, + num_bodies, + num_filters, + avg=True, + default=float("nan"), + ) + output["contact_normals_w"] = self._unpack_contact_buffer_data( + contact_normals, + buffer_count, + buffer_start_indices, + num_envs, + num_bodies, + num_filters, + avg=True, + default=float("nan"), + ) + output["contact_distances"] = self._unpack_contact_buffer_data( + contact_distances.view(-1, 1), + buffer_count, + buffer_start_indices, + num_envs, + num_bodies, + num_filters, + avg=True, + default=float("nan"), + ).squeeze(-1) + + method = getattr(view, "get_friction_data", None) + if method is not None: + data = method(dt=dt) + if isinstance(data, tuple) and len(data) >= 4: + friction_forces, _, buffer_count, buffer_start_indices = data[:4] + if num_envs > 0 and num_bodies > 0 and num_filters > 0: + output["friction_forces_w"] = self._unpack_contact_buffer_data( + friction_forces, + buffer_count, + buffer_start_indices, + num_envs, + num_bodies, + num_filters, + avg=False, + default=0.0, + ) + + if not output: + return None + return output + except Exception as exc: + logger.debug(f"[SceneDataProvider] Failed to read ContactView data: {exc}") + return None + + def _unpack_contact_buffer_data( + self, + contact_data, + buffer_count, + buffer_start_indices, + num_envs: int, + num_bodies: int, + num_filters: int, + avg: bool = True, + default: float = float("nan"), + ): + try: + import torch + + if num_envs <= 0 or num_bodies <= 0 or num_filters <= 0: + return None + + counts = buffer_count.view(-1) + starts = buffer_start_indices.view(-1) + n_rows = counts.numel() + if contact_data is None or n_rows == 0: + return None + + data = contact_data + if data.ndim == 1: + data = data.view(-1, 1) + dim = data.shape[-1] + + agg = torch.full((n_rows, dim), default, device=data.device, dtype=data.dtype) + total = int(counts.sum().item()) + if total > 0: + row_ids = torch.repeat_interleave(torch.arange(n_rows, device=data.device), counts) + block_starts = counts.cumsum(0) - counts + deltas = torch.arange(row_ids.numel(), device=data.device) - block_starts.repeat_interleave(counts) + flat_idx = starts[row_ids] + deltas + pts = data.index_select(0, flat_idx) + agg = agg.zero_().index_add_(0, row_ids, pts) + agg = agg / counts.clamp_min(1).unsqueeze(-1) if avg else agg + agg[counts == 0] = default + + return agg.view(num_envs, num_bodies, num_filters, dim) + except Exception: + return None + + def _get_xform_world_poses(self): + if not self._rigid_body_paths: + return None, None + try: + import torch + + from isaaclab.sim.views import XformPrimView + + positions = [] + orientations = [] + for path in self._rigid_body_paths: + view = self._xform_views.get(path) + if view is None: + view = XformPrimView(path, device=self._device, stage=self._stage, validate_xform_ops=False) + self._xform_views[path] = view + pos, quat = view.get_world_poses() + positions.append(pos) + orientations.append(quat) + return (torch.cat(positions, dim=0), torch.cat(orientations, dim=0)) if positions else (None, None) + except Exception as exc: + logger.debug(f"[SceneDataProvider] Failed to read XformPrimView poses: {exc}") + return None, None + + def _get_set_body_q_kernel(self): + if self._set_body_q_kernel is not None: + return self._set_body_q_kernel + try: + import warp as wp + + @wp.kernel(enable_backward=False) + def _set_body_q( + positions: wp.array(dtype=wp.vec3), + orientations: wp.array(dtype=wp.quatf), + body_q: wp.array(dtype=wp.transformf), + ): + i = wp.tid() + body_q[i] = wp.transformf(positions[i], orientations[i]) + + self._set_body_q_kernel = _set_body_q + return self._set_body_q_kernel + except Exception as exc: + logger.warning(f"[SceneDataProvider] Warp unavailable for Newton state sync: {exc}") + return None + + def update(self) -> None: + if not (self._has_newton_visualizer or self._has_rerun_visualizer): + return + self._refresh_newton_model_if_needed() + if self._newton_state is None: + return + if self._rigid_body_view is None and self._articulation_view is None and not self._rigid_body_paths: + return + + try: + import torch + import warp as wp + + from isaaclab.utils.math import convert_quat + + expected_count = self._newton_state.body_q.shape[0] + pose_sources = ( + ("articulation_view", lambda: self._get_view_world_poses(self._articulation_view)), + ("rigid_body_view", lambda: self._get_view_world_poses(self._rigid_body_view)), + ("xform_view", self._get_xform_world_poses), + ) + positions = orientations = None + source_view = "none" + for name, getter in pose_sources: + positions, orientations = getter() + if positions is not None and orientations is not None: + if positions.reshape(-1, 3).shape[0] == expected_count: + source_view = name + break + if positions is None or orientations is None: + return + order = self._view_body_index_map.get(source_view) + if order: + positions = positions[order] + orientations = orientations[order] + + positions = positions.reshape(-1, 3).to(dtype=torch.float32, device=self._device) + orientations = orientations.reshape(-1, 4).to(dtype=torch.float32, device=self._device) + # TODO(mtrepte) currently converting quaternion convention from wxyz to xyzw + # in the future, we can avoid this step + orientations_xyzw = convert_quat(orientations, to="xyzw") + + positions_wp = wp.from_torch(positions, dtype=wp.vec3) + orientations_wp = wp.from_torch(orientations_xyzw, dtype=wp.quatf) + + set_body_q = self._get_set_body_q_kernel() + if set_body_q is None: + return + + if positions_wp.shape[0] != expected_count: + logger.debug( + "[SceneDataProvider] Body count mismatch for Newton sync " + f"(poses={positions_wp.shape[0]}, state={expected_count}, source={source_view})." + ) + return + + wp.launch( + set_body_q, + dim=positions_wp.shape[0], + inputs=[positions_wp, orientations_wp, self._newton_state.body_q], + device=self._device, + ) + + # Future extensions: + # - Populate velocities into self._newton_state.body_qd + # - Sync contacts into Newton Contacts for richer debug visualizations + # - Cache mesh/material data for Rerun/renderer integrations + except Exception as exc: + logger.debug(f"[SceneDataProvider] Failed to sync Omni transforms to Newton state: {exc}") + + def get_model(self): + if not (self._has_newton_visualizer or self._has_rerun_visualizer): + return None + return self._newton_model + + def get_state(self): + if not (self._has_newton_visualizer or self._has_rerun_visualizer): + return None + return self._newton_state + + def get_metadata(self) -> dict[str, Any]: + return dict(self._metadata) + + def get_transforms(self) -> dict[str, Any] | None: + if self._rigid_body_view is None and self._articulation_view is None: + return None + try: + for getter in ( + lambda: self._get_view_world_poses(self._articulation_view), + lambda: self._get_view_world_poses(self._rigid_body_view), + self._get_xform_world_poses, + ): + positions, orientations = getter() + if positions is not None and orientations is not None: + return {"positions": positions, "orientations": orientations} + return None + except Exception: + return None + + def get_velocities(self) -> dict[str, Any] | None: + for source, view in ( + ("articulation_view", self._articulation_view), + ("rigid_body_view", self._rigid_body_view), + ): + linear, angular = self._get_view_velocities(view) + if linear is not None and angular is not None: + return {"linear": linear, "angular": angular, "source": source} + return None + + def get_contacts(self) -> dict[str, Any] | None: + if self._contact_view is None: + self._setup_contact_view() + data = self._get_view_contacts(self._contact_view) + if data is None: + return None + data["source"] = "contact_view" + return data diff --git a/source/isaaclab/isaaclab/sim/scene_data_providers/scene_data_provider.py b/source/isaaclab/isaaclab/sim/scene_data_providers/scene_data_provider.py new file mode 100644 index 00000000000..a999315d4af --- /dev/null +++ b/source/isaaclab/isaaclab/sim/scene_data_providers/scene_data_provider.py @@ -0,0 +1,124 @@ +#!/usr/bin/env python3 +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Scene data provider abstraction for visualizers and renderers.""" + +from __future__ import annotations + +import logging +from abc import ABC, abstractmethod +from typing import Any + +logger = logging.getLogger(__name__) + + +class SceneDataProviderBase(ABC): + """Base interface for scene data providers.""" + + @abstractmethod + def update(self) -> None: + """Sync any per-step data needed by visualizers.""" + + @abstractmethod + def get_model(self): + """Return a physics-backend model object, if applicable.""" + + @abstractmethod + def get_state(self): + """Return a physics-backend state object, if applicable.""" + + @abstractmethod + def get_metadata(self) -> dict[str, Any]: + """Return basic metadata about the scene/backend.""" + + @abstractmethod + def get_transforms(self) -> dict[str, Any] | None: + """Return transform data keyed by semantic names.""" + + def get_velocities(self) -> dict[str, Any] | None: + """Return velocity data keyed by semantic names.""" + # TODO: Populate linear/angular velocities once available per backend. + return None + + def get_contacts(self) -> dict[str, Any] | None: + """Return contact data keyed by semantic names.""" + # TODO: Populate contact data once available per backend. + return None + + def get_meshes(self) -> dict[str, Any] | None: + """Return mesh/material data keyed by semantic names.""" + # TODO: Populate mesh/material data once available per backend. + return None + + +class SceneDataProvider: + """Facade that selects the correct scene data provider for the active backend.""" + + def __init__( + self, + backend: str, + visualizer_cfgs: list[Any] | None, + stage=None, + simulation_context=None, + ) -> None: + self._backend = backend + self._provider: SceneDataProviderBase | None = None + + if backend == "newton": + from .newton_scene_data_provider import NewtonSceneDataProvider + + self._provider = NewtonSceneDataProvider(visualizer_cfgs) + elif backend == "omni": + if stage is None or simulation_context is None: + logger.warning( + "Omni scene data provider requires stage and simulation context; skipping initialization." + ) + self._provider = None + else: + from .ov_scene_data_provider import OmniSceneDataProvider + + self._provider = OmniSceneDataProvider(visualizer_cfgs, stage, simulation_context) + else: + logger.warning(f"Unknown physics backend '{backend}'. No scene data provider created.") + + def update(self) -> None: + if self._provider is not None: + self._provider.update() + + def get_model(self): + if self._provider is None: + return None + return self._provider.get_model() + + def get_state(self): + if self._provider is None: + return None + return self._provider.get_state() + + def get_metadata(self) -> dict[str, Any]: + if self._provider is None: + return {} + return self._provider.get_metadata() + + def get_transforms(self) -> dict[str, Any] | None: + if self._provider is None: + return None + return self._provider.get_transforms() + + def get_velocities(self) -> dict[str, Any] | None: + if self._provider is None: + return None + return self._provider.get_velocities() + + def get_contacts(self) -> dict[str, Any] | None: + if self._provider is None: + return None + return self._provider.get_contacts() + + def get_meshes(self) -> dict[str, Any] | None: + if self._provider is None: + return None + return self._provider.get_meshes() diff --git a/source/isaaclab/isaaclab/sim/spawners/materials/visual_materials.py b/source/isaaclab/isaaclab/sim/spawners/materials/visual_materials.py index 21edc3cd2d7..713ce34749b 100644 --- a/source/isaaclab/isaaclab/sim/spawners/materials/visual_materials.py +++ b/source/isaaclab/isaaclab/sim/spawners/materials/visual_materials.py @@ -61,12 +61,19 @@ def spawn_preview_surface(prim_path: str, cfg: visual_materials_cfg.PreviewSurfa # handle scene creation on a custom stage. material_prim = UsdShade.Material.Define(stage, prim_path) if material_prim: - shader_prim = CreateShaderPrimFromSdrCommand( - parent_path=prim_path, - identifier="UsdPreviewSurface", - stage_or_context=stage, - prim_name="Shader", - ).do() + try: + shader_prim = CreateShaderPrimFromSdrCommand( + parent_path=prim_path, + identifier="UsdPreviewSurface", + stage_or_context=stage, + name="Shader", + ).do() + except TypeError: + shader_prim = CreateShaderPrimFromSdrCommand( + parent_path=prim_path, + identifier="UsdPreviewSurface", + stage_or_context=stage, + ).do() # bind the shader graph to the material if shader_prim: surface_out = shader_prim.GetOutput("surface") @@ -82,7 +89,16 @@ def spawn_preview_surface(prim_path: str, cfg: visual_materials_cfg.PreviewSurfa raise ValueError(f"A prim already exists at path: '{prim_path}'.") # obtain prim - prim = stage.GetPrimAtPath(f"{prim_path}/Shader") + prim = None + if shader_prim: + if hasattr(shader_prim, "GetPrim"): + prim = shader_prim.GetPrim() + elif hasattr(shader_prim, "IsValid"): + prim = shader_prim + elif hasattr(shader_prim, "GetPath"): + prim = stage.GetPrimAtPath(str(shader_prim.GetPath())) + if prim is None or not prim.IsValid(): + prim = stage.GetPrimAtPath(f"{prim_path}/Shader") # check prim is valid if not prim.IsValid(): raise ValueError(f"Failed to create preview surface material at path: '{prim_path}'.") diff --git a/source/isaaclab/isaaclab/utils/simulation_runner.py b/source/isaaclab/isaaclab/utils/simulation_runner.py new file mode 100644 index 00000000000..1b0b89a031e --- /dev/null +++ b/source/isaaclab/isaaclab/utils/simulation_runner.py @@ -0,0 +1,37 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Utility functions for running simulation loops with visualizer-agnostic is_running checks.""" + +from __future__ import annotations + +from typing import TYPE_CHECKING, Any + +if TYPE_CHECKING: + from isaaclab.sim import SimulationContext + + +def is_simulation_running(simulation_app: Any | None, sim_context: SimulationContext | None = None) -> bool: + """Check if the simulation should continue running. + + - Omniverse mode: delegates to SimulationApp.is_running() + - Standalone mode with visualizers: checks if any visualizer window is still open + - Headless mode (no visualizers): always returns True (use Ctrl+C or break to exit) + """ + if simulation_app is not None: + return simulation_app.is_running() + + if sim_context is not None and hasattr(sim_context, "_visualizers"): + visualizers = sim_context._visualizers + if visualizers: + return any(v.is_running() for v in visualizers) + + return True + + +def close_simulation(simulation_app: Any | None) -> None: + """Close the simulation app if running in Omniverse mode.""" + if simulation_app is not None: + simulation_app.close() diff --git a/source/isaaclab/isaaclab/visualizers/__init__.py b/source/isaaclab/isaaclab/visualizers/__init__.py index 0667607f410..5ec6cd5f6bd 100644 --- a/source/isaaclab/isaaclab/visualizers/__init__.py +++ b/source/isaaclab/isaaclab/visualizers/__init__.py @@ -3,7 +3,6 @@ # # SPDX-License-Identifier: BSD-3-Clause - """Visualizer Registry. This module uses a registry pattern to decouple visualizer instantiation @@ -13,39 +12,55 @@ from __future__ import annotations -# Import base classes first +from typing import TYPE_CHECKING, Any + +from .newton_visualizer_cfg import NewtonVisualizerCfg +from .ov_visualizer_cfg import OVVisualizerCfg +from .rerun_visualizer_cfg import RerunVisualizerCfg from .visualizer import Visualizer from .visualizer_cfg import VisualizerCfg -# Global registry for visualizer types (lazy-loaded) -_VISUALIZER_REGISTRY: dict[str, type[Visualizer]] = {} +if TYPE_CHECKING: + from .newton_visualizer import NewtonVisualizer + from .ov_visualizer import OVVisualizer + from .rerun_visualizer import RerunVisualizer +_VISUALIZER_REGISTRY: dict[str, Any] = {} -def get_visualizer_class(name: str) -> type[Visualizer] | None: - """Get a visualizer class by name (lazy-loaded). +__all__ = [ + "Visualizer", + "VisualizerCfg", + "NewtonVisualizerCfg", + "OVVisualizerCfg", + "RerunVisualizerCfg", + "get_visualizer_class", +] - Args: - name: Visualizer type name (e.g., 'omniverse'). - Returns: - Visualizer class if found, None otherwise. - """ - # Check if already loaded +def get_visualizer_class(name: str) -> type[Visualizer] | None: + """Get a visualizer class by name (lazy-loaded).""" if name in _VISUALIZER_REGISTRY: return _VISUALIZER_REGISTRY[name] - # Lazy-load visualizer classes from backend packages - if name == "omniverse": - from isaaclab_physx.visualizers import OVVisualizer + try: + if name == "newton": + from .newton_visualizer import NewtonVisualizer - _VISUALIZER_REGISTRY["omniverse"] = OVVisualizer - return OVVisualizer + _VISUALIZER_REGISTRY["newton"] = NewtonVisualizer + return NewtonVisualizer + if name == "omniverse": + from .ov_visualizer import OVVisualizer - return None + _VISUALIZER_REGISTRY["omniverse"] = OVVisualizer + return OVVisualizer + if name == "rerun": + from .rerun_visualizer import RerunVisualizer + _VISUALIZER_REGISTRY["rerun"] = RerunVisualizer + return RerunVisualizer + return None + except ImportError as exc: + import warnings -__all__ = [ - "Visualizer", - "VisualizerCfg", - "get_visualizer_class", -] + warnings.warn(f"Failed to load visualizer '{name}': {exc}", ImportWarning) + return None diff --git a/source/isaaclab/isaaclab/visualizers/newton_visualizer.py b/source/isaaclab/isaaclab/visualizers/newton_visualizer.py new file mode 100644 index 00000000000..b3c01fedb8a --- /dev/null +++ b/source/isaaclab/isaaclab/visualizers/newton_visualizer.py @@ -0,0 +1,333 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Newton OpenGL Visualizer implementation.""" + +from __future__ import annotations + +import contextlib +import numpy as np +from typing import Any + +import warp as wp +from newton.viewer import ViewerGL + +from .newton_visualizer_cfg import NewtonVisualizerCfg +from .visualizer import Visualizer + + +class NewtonViewerGL(ViewerGL): + """Wrapper around Newton's ViewerGL with training/rendering pause controls.""" + + def __init__(self, *args, metadata: dict | None = None, update_frequency: int = 1, **kwargs): + super().__init__(*args, **kwargs) + self._paused_training = False + self._paused_rendering = False + self._metadata = metadata or {} + self._fallback_draw_controls = False + self._update_frequency = update_frequency + + try: + self.register_ui_callback(self._render_training_controls, position="side") + except AttributeError: + self._fallback_draw_controls = True + + def is_training_paused(self) -> bool: + return self._paused_training + + def is_rendering_paused(self) -> bool: + return self._paused_rendering + + def _render_training_controls(self, imgui): + imgui.separator() + imgui.text("IsaacLab Controls") + + pause_label = "Resume Training" if self._paused_training else "Pause Training" + if imgui.button(pause_label): + self._paused_training = not self._paused_training + + rendering_label = "Resume Rendering" if self._paused_rendering else "Pause Rendering" + if imgui.button(rendering_label): + self._paused_rendering = not self._paused_rendering + self._paused = self._paused_rendering + + imgui.text("Visualizer Update Frequency") + current_frequency = self._update_frequency + changed, new_frequency = imgui.slider_int( + "##VisualizerUpdateFreq", current_frequency, 1, 20, f"Every {current_frequency} frames" + ) + if changed: + self._update_frequency = new_frequency + + if imgui.is_item_hovered(): + imgui.set_tooltip( + "Controls visualizer update frequency\nlower values -> more responsive visualizer but slower" + " training\nhigher values -> less responsive visualizer but faster training" + ) + + def on_key_press(self, symbol, modifiers): + if self.ui.is_capturing(): + return + + try: + import pyglet # noqa: PLC0415 + except Exception: + return + + if symbol == pyglet.window.key.SPACE: + self._paused_rendering = not self._paused_rendering + self._paused = self._paused_rendering + return + + super().on_key_press(symbol, modifiers) + + def _render_ui(self): + if not self._fallback_draw_controls: + return super()._render_ui() + + super()._render_ui() + imgui = self.ui.imgui + from contextlib import suppress + + with suppress(Exception): + imgui.set_next_window_pos(imgui.ImVec2(320, 10)) + + flags = 0 + if imgui.begin("Training Controls", flags=flags): + self._render_training_controls(imgui) + imgui.end() + return None + + def _render_left_panel(self): + """Override the left panel to remove the base pause checkbox.""" + import newton as nt + + imgui = self.ui.imgui + nav_highlight_color = self.ui.get_theme_color(imgui.Col_.nav_cursor, (1.0, 1.0, 1.0, 1.0)) + + io = self.ui.io + imgui.set_next_window_pos(imgui.ImVec2(10, 10)) + imgui.set_next_window_size(imgui.ImVec2(300, io.display_size[1] - 20)) + + flags = imgui.WindowFlags_.no_resize.value + + if imgui.begin(f"Newton Viewer v{nt.__version__}", flags=flags): + imgui.separator() + + header_flags = 0 + + imgui.set_next_item_open(True, imgui.Cond_.appearing) + if imgui.collapsing_header("IsaacLab Options"): + for callback in self._ui_callbacks["side"]: + callback(self.ui.imgui) + + if self.model is not None: + imgui.set_next_item_open(True, imgui.Cond_.appearing) + if imgui.collapsing_header("Model Information", flags=header_flags): + imgui.separator() + num_envs = self._metadata.get("num_envs", 0) + imgui.text(f"Environments: {num_envs}") + axis_names = ["X", "Y", "Z"] + imgui.text(f"Up Axis: {axis_names[self.model.up_axis]}") + gravity = wp.to_torch(self.model.gravity)[0] + gravity_text = f"Gravity: ({gravity[0]:.2f}, {gravity[1]:.2f}, {gravity[2]:.2f})" + imgui.text(gravity_text) + + imgui.set_next_item_open(True, imgui.Cond_.appearing) + if imgui.collapsing_header("Visualization", flags=header_flags): + imgui.separator() + + show_joints = self.show_joints + changed, self.show_joints = imgui.checkbox("Show Joints", show_joints) + + show_contacts = self.show_contacts + changed, self.show_contacts = imgui.checkbox("Show Contacts", show_contacts) + + show_springs = self.show_springs + changed, self.show_springs = imgui.checkbox("Show Springs", show_springs) + + show_com = self.show_com + changed, self.show_com = imgui.checkbox("Show Center of Mass", show_com) + + imgui.set_next_item_open(True, imgui.Cond_.appearing) + if imgui.collapsing_header("Rendering Options"): + imgui.separator() + + changed, self.renderer.draw_sky = imgui.checkbox("Sky", self.renderer.draw_sky) + changed, self.renderer.draw_shadows = imgui.checkbox("Shadows", self.renderer.draw_shadows) + changed, self.renderer.draw_wireframe = imgui.checkbox("Wireframe", self.renderer.draw_wireframe) + + changed, self.renderer._light_color = imgui.color_edit3("Light Color", self.renderer._light_color) + changed, self.renderer.sky_upper = imgui.color_edit3("Sky Color", self.renderer.sky_upper) + changed, self.renderer.sky_lower = imgui.color_edit3("Ground Color", self.renderer.sky_lower) + + imgui.set_next_item_open(True, imgui.Cond_.appearing) + if imgui.collapsing_header("Camera"): + imgui.separator() + + pos = self.camera.pos + pos_text = f"Position: ({pos[0]:.2f}, {pos[1]:.2f}, {pos[2]:.2f})" + imgui.text(pos_text) + imgui.text(f"FOV: {self.camera.fov:.1f}°") + imgui.text(f"Yaw: {self.camera.yaw:.1f}°") + imgui.text(f"Pitch: {self.camera.pitch:.1f}°") + + imgui.separator() + imgui.push_style_color(imgui.Col_.text, imgui.ImVec4(*nav_highlight_color)) + imgui.text("Controls:") + imgui.pop_style_color() + imgui.text("WASD - Forward/Left/Back/Right") + imgui.text("QE - Down/Up") + imgui.text("Left Click - Look around") + imgui.text("Scroll - Zoom") + imgui.text("Space - Pause/Resume Rendering") + imgui.text("H - Toggle UI") + imgui.text("ESC - Exit") + + imgui.end() + return + + +class NewtonVisualizer(Visualizer): + """Newton OpenGL visualizer for Isaac Lab.""" + + def __init__(self, cfg: NewtonVisualizerCfg): + super().__init__(cfg) + self.cfg: NewtonVisualizerCfg = cfg + self._viewer: NewtonViewerGL | None = None + self._sim_time = 0.0 + self._step_counter = 0 + self._model = None + self._state = None + self._update_frequency = cfg.update_frequency + self._scene_data_provider = None + + def initialize(self, scene_data: dict[str, Any] | None = None) -> None: + if self._is_initialized: + return + + if scene_data and "scene_data_provider" in scene_data: + self._scene_data_provider = scene_data["scene_data_provider"] + + metadata = {} + if self._scene_data_provider: + self._model = self._scene_data_provider.get_model() + self._state = self._scene_data_provider.get_state() + metadata = self._scene_data_provider.get_metadata() + else: + try: + from isaaclab.sim._impl.newton_manager import NewtonManager + + self._model = NewtonManager._model + self._state = NewtonManager._state_0 + metadata = { + "physics_backend": "newton", + "num_envs": NewtonManager._num_envs if NewtonManager._num_envs is not None else 0, + "gravity_vector": NewtonManager._gravity_vector, + "clone_physics_only": NewtonManager._clone_physics_only, + } + except Exception: + pass + + if self._model is None: + raise RuntimeError("Newton visualizer requires a Newton Model. Ensure a scene data provider is available.") + + self._viewer = NewtonViewerGL( + width=self.cfg.window_width, + height=self.cfg.window_height, + metadata=metadata, + update_frequency=self.cfg.update_frequency, + ) + + self._viewer.set_model(self._model) + self._viewer.set_world_offsets((0.0, 0.0, 0.0)) + self._viewer.camera.pos = wp.vec3(*self.cfg.camera_position) + self._viewer.up_axis = 2 # Z-up + + cam_pos = np.array(self.cfg.camera_position, dtype=np.float32) + cam_target = np.array(self.cfg.camera_target, dtype=np.float32) + direction = cam_target - cam_pos + yaw = np.degrees(np.arctan2(direction[1], direction[0])) + horizontal_dist = np.sqrt(direction[0] ** 2 + direction[1] ** 2) + pitch = np.degrees(np.arctan2(direction[2], horizontal_dist)) + + self._viewer.camera.yaw = float(yaw) + self._viewer.camera.pitch = float(pitch) + + self._viewer.scaling = 1.0 + self._viewer._paused = False + + self._viewer.show_joints = self.cfg.show_joints + self._viewer.show_contacts = self.cfg.show_contacts + self._viewer.show_springs = self.cfg.show_springs + self._viewer.show_com = self.cfg.show_com + + self._viewer.renderer.draw_shadows = self.cfg.enable_shadows + self._viewer.renderer.draw_sky = self.cfg.enable_sky + self._viewer.renderer.draw_wireframe = self.cfg.enable_wireframe + + self._viewer.renderer.sky_upper = self.cfg.background_color + self._viewer.renderer.sky_lower = self.cfg.ground_color + self._viewer.renderer._light_color = self.cfg.light_color + + self._is_initialized = True + + def step(self, dt: float, state: Any | None = None) -> None: + if not self._is_initialized or self._is_closed or self._viewer is None: + return + + self._sim_time += dt + self._step_counter += 1 + + if self._scene_data_provider: + self._state = self._scene_data_provider.get_state() + else: + try: + from isaaclab.sim._impl.newton_manager import NewtonManager + + self._state = NewtonManager._state_0 + except Exception: + self._state = None + + update_frequency = self._viewer._update_frequency if self._viewer else self._update_frequency + if self._step_counter % update_frequency != 0: + return + + with contextlib.suppress(Exception): + if not self._viewer.is_paused(): + self._viewer.begin_frame(self._sim_time) + if self._state is not None: + self._viewer.log_state(self._state) + self._viewer.end_frame() + else: + self._viewer._update() + + def close(self) -> None: + if self._is_closed: + return + if self._viewer is not None: + self._viewer = None + self._is_closed = True + + def is_running(self) -> bool: + if not self._is_initialized or self._is_closed or self._viewer is None: + return False + return self._viewer.is_running() + + def supports_markers(self) -> bool: + return False + + def supports_live_plots(self) -> bool: + return False + + def is_training_paused(self) -> bool: + if not self._is_initialized or self._viewer is None: + return False + return self._viewer.is_training_paused() + + def is_rendering_paused(self) -> bool: + if not self._is_initialized or self._viewer is None: + return False + return self._viewer.is_rendering_paused() diff --git a/source/isaaclab/isaaclab/visualizers/newton_visualizer_cfg.py b/source/isaaclab/isaaclab/visualizers/newton_visualizer_cfg.py new file mode 100644 index 00000000000..0465c43ba6b --- /dev/null +++ b/source/isaaclab/isaaclab/visualizers/newton_visualizer_cfg.py @@ -0,0 +1,57 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Configuration for Newton OpenGL Visualizer.""" + +from isaaclab.utils import configclass + +from .visualizer_cfg import VisualizerCfg + + +@configclass +class NewtonVisualizerCfg(VisualizerCfg): + """Configuration for Newton OpenGL visualizer.""" + + visualizer_type: str = "newton" + """Type identifier for Newton visualizer.""" + + window_width: int = 1920 + """Window width in pixels.""" + + window_height: int = 1080 + """Window height in pixels.""" + + update_frequency: int = 1 + """Visualizer update frequency (updates every N frames).""" + + show_joints: bool = False + """Show joint visualization.""" + + show_contacts: bool = False + """Show contact visualization.""" + + show_springs: bool = False + """Show spring visualization.""" + + show_com: bool = False + """Show center of mass visualization.""" + + enable_shadows: bool = True + """Enable shadow rendering.""" + + enable_sky: bool = True + """Enable sky rendering.""" + + enable_wireframe: bool = False + """Enable wireframe rendering.""" + + background_color: tuple[float, float, float] = (0.53, 0.81, 0.92) + """Background/sky color RGB [0,1].""" + + ground_color: tuple[float, float, float] = (0.18, 0.20, 0.25) + """Ground color RGB [0,1].""" + + light_color: tuple[float, float, float] = (1.0, 1.0, 1.0) + """Light color RGB [0,1].""" diff --git a/source/isaaclab/isaaclab/visualizers/ov_visualizer.py b/source/isaaclab/isaaclab/visualizers/ov_visualizer.py new file mode 100644 index 00000000000..cd16c203ea9 --- /dev/null +++ b/source/isaaclab/isaaclab/visualizers/ov_visualizer.py @@ -0,0 +1,276 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Omniverse-based visualizer using Isaac Sim viewport.""" + +from __future__ import annotations + +import asyncio +import logging +from typing import Any + +from pxr import UsdGeom + +from .ov_visualizer_cfg import OVVisualizerCfg +from .visualizer import Visualizer + +logger = logging.getLogger(__name__) + + +class OVVisualizer(Visualizer): + """Omniverse visualizer using Isaac Sim viewport.""" + + def __init__(self, cfg: OVVisualizerCfg): + super().__init__(cfg) + self.cfg: OVVisualizerCfg = cfg + + self._simulation_app = None + self._viewport_window = None + self._viewport_api = None + self._is_initialized = False + self._sim_time = 0.0 + self._step_counter = 0 + + def initialize(self, scene_data: dict[str, Any] | None = None) -> None: + if self._is_initialized: + logger.warning("[OVVisualizer] Already initialized.") + return + + usd_stage = None + simulation_context = None + if scene_data is not None: + usd_stage = scene_data.get("usd_stage") + simulation_context = scene_data.get("simulation_context") + + if usd_stage is None: + raise RuntimeError("OV visualizer requires a USD stage.") + + metadata = {} + if simulation_context is not None: + num_envs = 0 + if hasattr(simulation_context, "scene") and simulation_context.scene is not None: + if hasattr(simulation_context.scene, "num_envs"): + num_envs = simulation_context.scene.num_envs + + metadata = { + "num_envs": num_envs, + "physics_backend": "omni", + "env_prim_pattern": "/World/envs/env_{}", + } + + self._ensure_simulation_app() + self._setup_viewport(usd_stage, metadata) + + num_envs = metadata.get("num_envs", 0) + physics_backend = metadata.get("physics_backend", "unknown") + logger.info(f"[OVVisualizer] Initialized ({num_envs} envs, {physics_backend} physics)") + + self._is_initialized = True + + def step(self, dt: float, state: Any | None = None) -> None: + if not self._is_initialized: + return + self._sim_time += dt + self._step_counter += 1 + + def close(self) -> None: + if not self._is_initialized: + return + self._simulation_app = None + self._viewport_window = None + self._viewport_api = None + self._is_initialized = False + + def is_running(self) -> bool: + if self._simulation_app is None: + return False + return self._simulation_app.is_running() + + def is_training_paused(self) -> bool: + return False + + def supports_markers(self) -> bool: + return True + + def supports_live_plots(self) -> bool: + return True + + def set_camera_view( + self, eye: tuple[float, float, float] | list[float], target: tuple[float, float, float] | list[float] + ) -> None: + if not self._is_initialized: + logger.warning("[OVVisualizer] Cannot set camera view - visualizer not initialized.") + return + self._set_viewport_camera(tuple(eye), tuple(target)) + + def _ensure_simulation_app(self) -> None: + try: + import omni.kit.app + + app = omni.kit.app.get_app() + if app is None or not app.is_running(): + raise RuntimeError( + "[OVVisualizer] No Isaac Sim app is running. " + "OV visualizer requires Isaac Sim to be launched before initialization." + ) + + try: + from isaacsim import SimulationApp + + sim_app = None + if hasattr(SimulationApp, "_instance") and SimulationApp._instance is not None: + sim_app = SimulationApp._instance + elif hasattr(SimulationApp, "instance") and callable(SimulationApp.instance): + sim_app = SimulationApp.instance() + + if sim_app is not None: + self._simulation_app = sim_app + if self._simulation_app.config.get("headless", False): + logger.warning( + "[OVVisualizer] Running in headless mode. " + "OV visualizer requires GUI mode (launch with --headless=False)." + ) + else: + logger.info("[OVVisualizer] Using existing Isaac Sim app instance.") + else: + logger.info("[OVVisualizer] Isaac Sim app is running (via omni.kit.app).") + except ImportError: + logger.info("[OVVisualizer] Using running Isaac Sim app (SimulationApp module not available).") + except ImportError as exc: + raise ImportError( + f"[OVVisualizer] Could not import omni.kit.app: {exc}. Isaac Sim may not be installed or not running." + ) + + def _setup_viewport(self, usd_stage, metadata: dict) -> None: + try: + import omni.kit.viewport.utility as vp_utils + from omni.ui import DockPosition + + if self.cfg.create_viewport and self.cfg.viewport_name: + dock_position_map = { + "LEFT": DockPosition.LEFT, + "RIGHT": DockPosition.RIGHT, + "BOTTOM": DockPosition.BOTTOM, + "SAME": DockPosition.SAME, + } + dock_pos = dock_position_map.get(self.cfg.dock_position.upper(), DockPosition.SAME) + + self._viewport_window = vp_utils.create_viewport_window( + name=self.cfg.viewport_name, + width=self.cfg.window_width, + height=self.cfg.window_height, + position_x=50, + position_y=50, + docked=True, + ) + + logger.info(f"[OVVisualizer] Created viewport '{self.cfg.viewport_name}'") + asyncio.ensure_future(self._dock_viewport_async(self.cfg.viewport_name, dock_pos)) + + if self._viewport_window: + self._create_and_assign_camera(usd_stage) + else: + if self.cfg.viewport_name: + self._viewport_window = vp_utils.get_viewport_window_by_name(self.cfg.viewport_name) + if self._viewport_window is None: + logger.warning( + f"[OVVisualizer] Viewport '{self.cfg.viewport_name}' not found. Using active viewport." + ) + self._viewport_window = vp_utils.get_active_viewport_window() + else: + logger.info(f"[OVVisualizer] Using existing viewport '{self.cfg.viewport_name}'") + else: + self._viewport_window = vp_utils.get_active_viewport_window() + logger.info("[OVVisualizer] Using existing active viewport") + + if self._viewport_window is None: + logger.warning("[OVVisualizer] Could not get/create viewport.") + return + + self._viewport_api = self._viewport_window.viewport_api + self._set_viewport_camera(self.cfg.camera_position, self.cfg.camera_target) + logger.info(f"[OVVisualizer] Viewport configured (size: {self.cfg.window_width}x{self.cfg.window_height})") + except ImportError as exc: + logger.warning(f"[OVVisualizer] Viewport utilities unavailable: {exc}") + except Exception as exc: + logger.error(f"[OVVisualizer] Error setting up viewport: {exc}") + + async def _dock_viewport_async(self, viewport_name: str, dock_position) -> None: + try: + import omni.kit.app + import omni.ui + + viewport_window = None + for i in range(10): + viewport_window = omni.ui.Workspace.get_window(viewport_name) + if viewport_window: + logger.info(f"[OVVisualizer] Found viewport window '{viewport_name}' after {i} frames") + break + await omni.kit.app.get_app().next_update_async() + + if not viewport_window: + logger.warning(f"[OVVisualizer] Could not find viewport window '{viewport_name}' in workspace.") + return + + main_viewport = omni.ui.Workspace.get_window("Viewport") + if not main_viewport: + for alt_name in ["/OmniverseKit/Viewport", "Viewport Next"]: + main_viewport = omni.ui.Workspace.get_window(alt_name) + if main_viewport: + break + + if main_viewport and main_viewport != viewport_window: + viewport_window.dock_in(main_viewport, dock_position, 0.5) + await omni.kit.app.get_app().next_update_async() + viewport_window.focus() + viewport_window.visible = True + await omni.kit.app.get_app().next_update_async() + viewport_window.focus() + + logger.info( + f"[OVVisualizer] Docked viewport '{viewport_name}' at position {self.cfg.dock_position} and set as" + " active" + ) + else: + logger.info( + f"[OVVisualizer] Could not find main viewport for docking. Viewport '{viewport_name}' will remain" + " floating." + ) + except Exception as exc: + logger.warning(f"[OVVisualizer] Error docking viewport: {exc}") + + def _create_and_assign_camera(self, usd_stage) -> None: + try: + camera_path = f"/World/Cameras/{self.cfg.viewport_name}_Camera" + camera_prim = usd_stage.GetPrimAtPath(camera_path) + if not camera_prim.IsValid(): + UsdGeom.Camera.Define(usd_stage, camera_path) + logger.info(f"[OVVisualizer] Created camera: {camera_path}") + else: + logger.info(f"[OVVisualizer] Using existing camera: {camera_path}") + + if self._viewport_api: + self._viewport_api.set_active_camera(camera_path) + logger.info(f"[OVVisualizer] Assigned camera '{camera_path}' to viewport '{self.cfg.viewport_name}'") + except Exception as exc: + logger.warning(f"[OVVisualizer] Could not create/assign camera: {exc}. Using default camera.") + + def _set_viewport_camera(self, position: tuple[float, float, float], target: tuple[float, float, float]) -> None: + if self._viewport_api is None: + return + + try: + import isaacsim.core.utils.viewports as vp_utils + + camera_path = self._viewport_api.get_active_camera() + if not camera_path: + camera_path = "/OmniverseKit_Persp" + + vp_utils.set_camera_view( + eye=list(position), target=list(target), camera_prim_path=camera_path, viewport_api=self._viewport_api + ) + logger.info(f"[OVVisualizer] Camera set: pos={position}, target={target}, camera={camera_path}") + except Exception as exc: + logger.warning(f"[OVVisualizer] Could not set camera: {exc}") diff --git a/source/isaaclab/isaaclab/visualizers/ov_visualizer_cfg.py b/source/isaaclab/isaaclab/visualizers/ov_visualizer_cfg.py new file mode 100644 index 00000000000..33099ef34f8 --- /dev/null +++ b/source/isaaclab/isaaclab/visualizers/ov_visualizer_cfg.py @@ -0,0 +1,33 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Configuration for Omniverse-based visualizer.""" + +from isaaclab.utils import configclass + +from .visualizer_cfg import VisualizerCfg + + +@configclass +class OVVisualizerCfg(VisualizerCfg): + """Configuration for Omniverse visualizer using Isaac Sim viewport.""" + + visualizer_type: str = "omniverse" + """Type identifier for Omniverse visualizer.""" + + viewport_name: str | None = "Visualizer Viewport" + """Viewport name to use. If None, uses active viewport.""" + + create_viewport: bool = True + """Create new viewport with specified name and camera pose.""" + + dock_position: str = "SAME" + """Dock position for new viewport. Options: 'LEFT', 'RIGHT', 'BOTTOM', 'SAME'.""" + + window_width: int = 1280 + """Viewport width in pixels.""" + + window_height: int = 720 + """Viewport height in pixels.""" diff --git a/source/isaaclab/isaaclab/visualizers/rerun_visualizer.py b/source/isaaclab/isaaclab/visualizers/rerun_visualizer.py new file mode 100644 index 00000000000..f75555096cc --- /dev/null +++ b/source/isaaclab/isaaclab/visualizers/rerun_visualizer.py @@ -0,0 +1,225 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Rerun-based visualizer using rerun-sdk.""" + +from __future__ import annotations + +import logging +from typing import Any + +from .rerun_visualizer_cfg import RerunVisualizerCfg +from .visualizer import Visualizer + +logger = logging.getLogger(__name__) + +try: + import rerun as rr + import rerun.blueprint as rrb + from newton.viewer import ViewerRerun + + _RERUN_AVAILABLE = True +except ImportError: + rr = None + rrb = None + ViewerRerun = None + _RERUN_AVAILABLE = False + + +class NewtonViewerRerun(ViewerRerun if _RERUN_AVAILABLE else object): + """Isaac Lab wrapper for Newton's ViewerRerun.""" + + def __init__( + self, + app_id: str | None = None, + web_port: int | None = None, + keep_historical_data: bool = False, + keep_scalar_history: bool = True, + record_to_rrd: str | None = None, + metadata: dict | None = None, + ): + super().__init__( + app_id=app_id, + web_port=web_port, + serve_web_viewer=True, + keep_historical_data=keep_historical_data, + keep_scalar_history=keep_scalar_history, + record_to_rrd=record_to_rrd, + ) + + self._metadata = metadata or {} + self._log_metadata() + + def _log_metadata(self) -> None: + metadata_text = "# Isaac Lab Scene Metadata\n\n" + physics_backend = self._metadata.get("physics_backend", "unknown") + metadata_text += f"**Physics Backend:** {physics_backend}\n" + num_envs = self._metadata.get("num_envs", 0) + metadata_text += f"**Total Environments:** {num_envs}\n" + + for key, value in self._metadata.items(): + if key not in ["physics_backend", "num_envs"]: + metadata_text += f"**{key}:** {value}\n" + + rr.log("metadata", rr.TextDocument(metadata_text, media_type=rr.MediaType.MARKDOWN)) + + +class RerunVisualizer(Visualizer): + """Rerun web-based visualizer with time scrubbing, recording, and data inspection.""" + + def __init__(self, cfg: RerunVisualizerCfg): + super().__init__(cfg) + self.cfg: RerunVisualizerCfg = cfg + + if not _RERUN_AVAILABLE: + raise ImportError("Rerun visualizer requires rerun-sdk and Newton. Install: pip install rerun-sdk") + + self._viewer: NewtonViewerRerun | None = None + self._model = None + self._state = None + self._is_initialized = False + self._sim_time = 0.0 + self._scene_data_provider = None + + def initialize(self, scene_data: dict[str, Any] | None = None) -> None: + if self._is_initialized: + logger.warning("[RerunVisualizer] Already initialized. Skipping re-initialization.") + return + + if scene_data and "scene_data_provider" in scene_data: + self._scene_data_provider = scene_data["scene_data_provider"] + + metadata = {} + if self._scene_data_provider: + self._model = self._scene_data_provider.get_model() + self._state = self._scene_data_provider.get_state() + metadata = self._scene_data_provider.get_metadata() + else: + try: + from isaaclab.sim._impl.newton_manager import NewtonManager + + self._model = NewtonManager._model + self._state = NewtonManager._state_0 + metadata = { + "physics_backend": "newton", + "num_envs": NewtonManager._num_envs if NewtonManager._num_envs is not None else 0, + "gravity_vector": NewtonManager._gravity_vector, + "clone_physics_only": NewtonManager._clone_physics_only, + } + except Exception: + pass + + if self._model is None: + raise RuntimeError( + "Rerun visualizer requires a Newton Model. Ensure a scene data provider is available." + ) + + if self._state is None: + logger.warning("[RerunVisualizer] No Newton State available. Visualization may not work correctly.") + + try: + if self.cfg.record_to_rrd: + logger.info(f"[RerunVisualizer] Recording enabled to: {self.cfg.record_to_rrd}") + + self._viewer = NewtonViewerRerun( + app_id=self.cfg.app_id, + web_port=self.cfg.web_port, + keep_historical_data=self.cfg.keep_historical_data, + keep_scalar_history=self.cfg.keep_scalar_history, + record_to_rrd=self.cfg.record_to_rrd, + metadata=metadata, + ) + + self._viewer.set_model(self._model) + self._viewer.set_world_offsets((0.0, 0.0, 0.0)) + + try: + cam_pos = self.cfg.camera_position + cam_target = self.cfg.camera_target + + blueprint = rrb.Blueprint( + rrb.Spatial3DView( + name="3D View", + origin="/", + eye_controls=rrb.EyeControls3D( + position=cam_pos, + look_target=cam_target, + ), + ), + collapse_panels=True, + ) + rr.send_blueprint(blueprint) + + logger.info(f"[RerunVisualizer] Set initial camera view: position={cam_pos}, target={cam_target}") + except Exception as exc: + logger.warning(f"[RerunVisualizer] Could not set initial camera view: {exc}") + + num_envs = metadata.get("num_envs", 0) + physics_backend = metadata.get("physics_backend", "unknown") + logger.info(f"[RerunVisualizer] Initialized with {num_envs} environments (physics: {physics_backend})") + + self._is_initialized = True + except Exception as exc: + logger.error(f"[RerunVisualizer] Failed to initialize viewer: {exc}") + raise + + def step(self, dt: float, state: Any | None = None) -> None: + if not self._is_initialized or self._viewer is None: + logger.warning("[RerunVisualizer] Not initialized. Call initialize() first.") + return + + if self._scene_data_provider: + self._state = self._scene_data_provider.get_state() + else: + try: + from isaaclab.sim._impl.newton_manager import NewtonManager + + self._state = NewtonManager._state_0 + except Exception: + self._state = None + + self._sim_time += dt + + self._viewer.begin_frame(self._sim_time) + if self._state is not None: + self._viewer.log_state(self._state) + self._viewer.end_frame() + + def close(self) -> None: + if not self._is_initialized or self._viewer is None: + return + + try: + if self.cfg.record_to_rrd: + logger.info(f"[RerunVisualizer] Finalizing recording to: {self.cfg.record_to_rrd}") + self._viewer.close() + logger.info("[RerunVisualizer] Closed successfully.") + if self.cfg.record_to_rrd: + import os + + if os.path.exists(self.cfg.record_to_rrd): + size = os.path.getsize(self.cfg.record_to_rrd) + logger.info(f"[RerunVisualizer] Recording saved: {self.cfg.record_to_rrd} ({size} bytes)") + else: + logger.warning(f"[RerunVisualizer] Recording file not found: {self.cfg.record_to_rrd}") + except Exception as exc: + logger.warning(f"[RerunVisualizer] Error during close: {exc}") + + self._viewer = None + self._is_initialized = False + + def is_running(self) -> bool: + if self._viewer is None: + return False + return self._viewer.is_running() + + def is_training_paused(self) -> bool: + return False + + def supports_markers(self) -> bool: + return False + + def supports_live_plots(self) -> bool: + return False diff --git a/source/isaaclab/isaaclab/visualizers/rerun_visualizer_cfg.py b/source/isaaclab/isaaclab/visualizers/rerun_visualizer_cfg.py new file mode 100644 index 00000000000..8b1e32d7ded --- /dev/null +++ b/source/isaaclab/isaaclab/visualizers/rerun_visualizer_cfg.py @@ -0,0 +1,35 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Configuration for the Rerun visualizer.""" + +from __future__ import annotations + +from isaaclab.utils import configclass + +from .visualizer_cfg import VisualizerCfg + + +@configclass +class RerunVisualizerCfg(VisualizerCfg): + """Configuration for Rerun visualizer (web-based visualization).""" + + visualizer_type: str = "rerun" + """Type identifier for Rerun visualizer.""" + + app_id: str = "isaaclab-simulation" + """Application identifier shown in viewer title.""" + + web_port: int = 9090 + """Port of the local rerun web viewer which is launched in the browser.""" + + keep_historical_data: bool = False + """Keep transform history for time scrubbing (False = constant memory for training).""" + + keep_scalar_history: bool = False + """Keep scalar/plot history in timeline.""" + + record_to_rrd: str | None = None + """Path to save .rrd recording file. None = no recording.""" diff --git a/source/isaaclab/isaaclab/visualizers/visualizer.py b/source/isaaclab/isaaclab/visualizers/visualizer.py index 79d3bf3606d..554582e94b3 100644 --- a/source/isaaclab/isaaclab/visualizers/visualizer.py +++ b/source/isaaclab/isaaclab/visualizers/visualizer.py @@ -29,7 +29,7 @@ def __init__(self, cfg: VisualizerCfg): @abstractmethod def initialize(self, scene_data: dict[str, Any] | None = None) -> None: """Initialize visualizer with scene data (model, state, usd_stage, etc.).""" - pass + raise NotImplementedError @abstractmethod def step(self, dt: float, state: Any | None = None) -> None: @@ -39,22 +39,17 @@ def step(self, dt: float, state: Any | None = None) -> None: dt: Time step in seconds. state: Updated physics state (e.g., newton.State). """ - pass + raise NotImplementedError @abstractmethod def close(self) -> None: """Clean up resources.""" - pass + raise NotImplementedError @abstractmethod def is_running(self) -> bool: """Check if visualizer is still running (e.g., window not closed).""" - pass - - @abstractmethod - def is_stopped(self) -> bool: - """Check if visualizer is stopped (e.g., window closed).""" - pass + raise NotImplementedError def is_training_paused(self) -> bool: """Check if training is paused by visualizer controls.""" diff --git a/source/isaaclab/isaaclab/visualizers/visualizer_cfg.py b/source/isaaclab/isaaclab/visualizers/visualizer_cfg.py index 370d1ad94e1..1b3e6777439 100644 --- a/source/isaaclab/isaaclab/visualizers/visualizer_cfg.py +++ b/source/isaaclab/isaaclab/visualizers/visualizer_cfg.py @@ -27,9 +27,6 @@ class VisualizerCfg: visualizer_type: str | None = None """Type identifier (e.g., 'newton', 'rerun', 'omniverse'). Must be overridden by subclasses.""" - # Note: Partial environment visualization will come later - # env_ids: list[Integer] = [] - enable_markers: bool = True """Enable visualization markers (debug drawing).""" @@ -74,6 +71,11 @@ def create_visualizer(self) -> Visualizer: visualizer_class = get_visualizer_class(self.visualizer_type) if visualizer_class is None: + if self.visualizer_type in ("newton", "rerun"): + raise ImportError( + f"Visualizer '{self.visualizer_type}' requires the Newton Python module and its dependencies. " + "Install the Newton backend (e.g., newton package/isaaclab_newton) and retry." + ) raise ValueError( f"Visualizer type '{self.visualizer_type}' is not registered. " "Valid types: 'newton', 'rerun', 'omniverse'." From b75b4196885484c0bc1d92b094a001179c1e47ec Mon Sep 17 00:00:00 2001 From: Matthew Trepte Date: Tue, 27 Jan 2026 18:09:30 +0000 Subject: [PATCH 30/46] wip: initial design for adding viz --- .../visualization.rst | 4 +- .../isaaclab/envs/manager_based_env.py | 2 +- .../isaaclab/scene/interactive_scene.py | 2 +- .../newton_scene_data_provider.py | 47 +++++++------- .../ov_scene_data_provider.py | 46 +++++++++---- .../scene_data_provider.py | 65 +++++++++++-------- .../isaaclab/sim/simulation_context.py | 7 +- .../isaaclab/visualizers/newton_visualizer.py | 29 +++++++-- .../visualizers/newton_visualizer_cfg.py | 8 +-- .../isaaclab/visualizers/ov_visualizer.py | 15 ++--- .../isaaclab/visualizers/rerun_visualizer.py | 6 +- source/isaaclab/setup.py | 10 +-- 12 files changed, 144 insertions(+), 97 deletions(-) diff --git a/docs/source/experimental-features/newton-physics-integration/visualization.rst b/docs/source/experimental-features/newton-physics-integration/visualization.rst index f5443573393..661a98cf9fe 100644 --- a/docs/source/experimental-features/newton-physics-integration/visualization.rst +++ b/docs/source/experimental-features/newton-physics-integration/visualization.rst @@ -213,8 +213,8 @@ Newton Visualizer enable_wireframe=False, # Enable wireframe mode # Color customization - background_color=(0.53, 0.81, 0.92), # Sky/background color (RGB [0,1]) - ground_color=(0.18, 0.20, 0.25), # Ground plane color (RGB [0,1]) + sky_upper_color=(0.53, 0.81, 0.92), # Sky upper color (RGB [0,1]) + sky_lower_color=(0.18, 0.20, 0.25), # Sky lower color (RGB [0,1]) light_color=(1.0, 1.0, 1.0), # Directional light color (RGB [0,1]) ) diff --git a/source/isaaclab/isaaclab/envs/manager_based_env.py b/source/isaaclab/isaaclab/envs/manager_based_env.py index 4bb9999b4ee..a4eda256acd 100644 --- a/source/isaaclab/isaaclab/envs/manager_based_env.py +++ b/source/isaaclab/isaaclab/envs/manager_based_env.py @@ -147,7 +147,7 @@ def __init__(self, cfg: ManagerBasedEnvCfg): "[SceneDebug] env prims after InteractiveScene: " f"num_envs_setting={self.cfg.scene.num_envs}, env_prims={len(env_prim_paths)}" ) - import ipdb; ipdb.set_trace() + # import ipdb; ipdb.set_trace() # set up camera viewport controller # viewport is not available in other rendering modes so the function will throw a warning diff --git a/source/isaaclab/isaaclab/scene/interactive_scene.py b/source/isaaclab/isaaclab/scene/interactive_scene.py index 20713c0f15e..96353d719a8 100644 --- a/source/isaaclab/isaaclab/scene/interactive_scene.py +++ b/source/isaaclab/isaaclab/scene/interactive_scene.py @@ -125,7 +125,7 @@ def __init__(self, cfg: InteractiveSceneCfg): self.cfg = cfg # TODO(mtrepte): remove - # self.cfg.clone_in_fabric = False + self.cfg.clone_in_fabric = False # initialize scene elements self._terrain = None diff --git a/source/isaaclab/isaaclab/sim/scene_data_providers/newton_scene_data_provider.py b/source/isaaclab/isaaclab/sim/scene_data_providers/newton_scene_data_provider.py index d664abbe343..7144b599b3a 100644 --- a/source/isaaclab/isaaclab/sim/scene_data_providers/newton_scene_data_provider.py +++ b/source/isaaclab/isaaclab/sim/scene_data_providers/newton_scene_data_provider.py @@ -17,25 +17,21 @@ class NewtonSceneDataProvider(SceneDataProviderBase): - """Newton-backed scene data provider (when Newton physics is the active backend).""" + """Scene data provider for Newton Warp physics backend. + + Native (cheap): Newton Model/State from NewtonManager + Adapted (future): USD stage (would need Newton→USD sync for OV visualizer) + """ def __init__(self, visualizer_cfgs: list[Any] | None) -> None: - self._has_newton_visualizer = False - self._has_rerun_visualizer = False self._has_ov_visualizer = False self._metadata: dict[str, Any] = {} if visualizer_cfgs: for cfg in visualizer_cfgs: - viz_type = getattr(cfg, "visualizer_type", None) - if viz_type == "newton": - self._has_newton_visualizer = True - elif viz_type == "rerun": - self._has_rerun_visualizer = True - elif viz_type == "omniverse": + if getattr(cfg, "visualizer_type", None) == "omniverse": self._has_ov_visualizer = True - # Lazy import to keep develop usable without Newton installed. try: from isaaclab.sim._impl.newton_manager import NewtonManager @@ -49,51 +45,54 @@ def __init__(self, visualizer_cfgs: list[Any] | None) -> None: self._metadata = {"physics_backend": "newton"} def update(self) -> None: - return None + """No-op for Newton backend (state updated by Newton solver).""" + pass - def get_model(self): - if not (self._has_newton_visualizer or self._has_rerun_visualizer): - return None + def get_newton_model(self) -> Any | None: + """NATIVE: Newton Model from NewtonManager.""" try: from isaaclab.sim._impl.newton_manager import NewtonManager - return NewtonManager._model except Exception: return None - def get_state(self): - if not (self._has_newton_visualizer or self._has_rerun_visualizer): - return None + def get_newton_state(self) -> Any | None: + """NATIVE: Newton State from NewtonManager.""" try: from isaaclab.sim._impl.newton_manager import NewtonManager - return NewtonManager._state_0 except Exception: return None + def get_usd_stage(self) -> None: + """UNAVAILABLE: Newton backend doesn't provide USD (future: Newton→USD sync).""" + return None + def get_metadata(self) -> dict[str, Any]: return dict(self._metadata) def get_transforms(self) -> dict[str, Any] | None: + """Extract transforms from Newton state (future work).""" return None def get_velocities(self) -> dict[str, Any] | None: try: from isaaclab.sim._impl.newton_manager import NewtonManager - - state = NewtonManager._state_0 - if state is None: + if NewtonManager._state_0 is None: return None - return {"body_qd": state.body_qd} + return {"body_qd": NewtonManager._state_0.body_qd} except Exception: return None def get_contacts(self) -> dict[str, Any] | None: try: from isaaclab.sim._impl.newton_manager import NewtonManager - if NewtonManager._contacts is None: return None return {"contacts": NewtonManager._contacts} except Exception: return None + + def get_mesh_data(self) -> dict[str, Any] | None: + """ADAPTED: Extract mesh data from Newton shapes (future work).""" + return None \ No newline at end of file diff --git a/source/isaaclab/isaaclab/sim/scene_data_providers/ov_scene_data_provider.py b/source/isaaclab/isaaclab/sim/scene_data_providers/ov_scene_data_provider.py index 52e5afd0fd9..462421d4073 100644 --- a/source/isaaclab/isaaclab/sim/scene_data_providers/ov_scene_data_provider.py +++ b/source/isaaclab/isaaclab/sim/scene_data_providers/ov_scene_data_provider.py @@ -4,11 +4,12 @@ # # SPDX-License-Identifier: BSD-3-Clause -"""Omni PhysX-backed scene data provider.""" +"""OV (Omniverse) scene data provider for Omni PhysX backend.""" from __future__ import annotations import logging +import os import re from typing import Any @@ -17,11 +18,13 @@ logger = logging.getLogger(__name__) -class OmniSceneDataProvider(SceneDataProviderBase): - """Omni PhysX-backed scene data provider. - - This provider can generate a Newton-compatible Model/State for use by Newton and Rerun - visualizers while the active physics backend is Omni PhysX. +class OVSceneDataProvider(SceneDataProviderBase): + """Scene data provider for Omni PhysX physics backend. + + Native (cheap): USD stage, PhysX transforms/velocities/contacts + Adapted (expensive): Newton Model/State (built from USD, synced each step) + + Performance: Only builds Newton data if Newton/Rerun visualizers are active. """ def __init__(self, visualizer_cfgs: list[Any] | None, stage, simulation_context) -> None: @@ -65,10 +68,13 @@ def __init__(self, visualizer_cfgs: list[Any] | None, stage, simulation_context) self._set_body_q_kernel = None self._up_axis = UsdGeom.GetStageUpAxis(self._stage) + # Only build Newton model if Newton/Rerun visualizers need it if self._has_newton_visualizer or self._has_rerun_visualizer: self._build_newton_model_from_usd() self._setup_rigid_body_view() self._setup_articulation_view() + elif self._has_ov_visualizer: + logger.info("[OVSceneDataProvider] OV visualizer only - skipping Newton model build") def _get_num_envs(self) -> int: try: @@ -115,7 +121,7 @@ def _build_newton_model_from_usd(self) -> None: num_envs = self._get_num_envs() - import ipdb; ipdb.set_trace() + # import ipdb; ipdb.set_trace() env_prim_paths = find_matching_prim_paths("/World/envs/env_.*", stage=self._stage) print( "[SceneDataProvider] Stage env prims before add_usd: "+ @@ -453,8 +459,9 @@ def _set_body_q( return None def update(self) -> None: + """Sync PhysX transforms to Newton state if Newton/Rerun visualizers are active.""" if not (self._has_newton_visualizer or self._has_rerun_visualizer): - return + return # OV visualizer only - USD auto-synced by omni.physics self._refresh_newton_model_if_needed() if self._newton_state is None: return @@ -490,9 +497,12 @@ def update(self) -> None: positions = positions.reshape(-1, 3).to(dtype=torch.float32, device=self._device) orientations = orientations.reshape(-1, 4).to(dtype=torch.float32, device=self._device) - # TODO(mtrepte) currently converting quaternion convention from wxyz to xyzw - # in the future, we can avoid this step - orientations_xyzw = convert_quat(orientations, to="xyzw") + # NOTE: PhysX tensor views return quats in xyzw, while XformPrimView returns wxyz. + # Convert only when needed to avoid scrambling orientations. + if source_view == "xform_view": + orientations_xyzw = convert_quat(orientations, to="xyzw") + else: + orientations_xyzw = orientations positions_wp = wp.from_torch(positions, dtype=wp.vec3) orientations_wp = wp.from_torch(orientations_xyzw, dtype=wp.quatf) @@ -522,16 +532,26 @@ def update(self) -> None: except Exception as exc: logger.debug(f"[SceneDataProvider] Failed to sync Omni transforms to Newton state: {exc}") - def get_model(self): + def get_newton_model(self) -> Any | None: + """ADAPTED: Newton Model built from USD (only if Newton/Rerun visualizers active).""" if not (self._has_newton_visualizer or self._has_rerun_visualizer): return None return self._newton_model - def get_state(self): + def get_newton_state(self) -> Any | None: + """ADAPTED: Newton State synced from PhysX (only if Newton/Rerun visualizers active).""" if not (self._has_newton_visualizer or self._has_rerun_visualizer): return None return self._newton_state + def get_usd_stage(self) -> Any: + """NATIVE: USD stage.""" + return self._stage + + def get_mesh_data(self) -> dict[str, Any] | None: + """NATIVE: Extract mesh data from USD stage (future work).""" + return None + def get_metadata(self) -> dict[str, Any]: return dict(self._metadata) diff --git a/source/isaaclab/isaaclab/sim/scene_data_providers/scene_data_provider.py b/source/isaaclab/isaaclab/sim/scene_data_providers/scene_data_provider.py index a999315d4af..dae8ee5c468 100644 --- a/source/isaaclab/isaaclab/sim/scene_data_providers/scene_data_provider.py +++ b/source/isaaclab/isaaclab/sim/scene_data_providers/scene_data_provider.py @@ -16,46 +16,52 @@ class SceneDataProviderBase(ABC): - """Base interface for scene data providers.""" + """Base interface for scene data providers. + + Provides simulation data in multiple formats for visualizers, renderers, + and other downstream consumers. Each backend provider implements this interface, + exposing native data cheaply and adapted data when needed. + """ @abstractmethod def update(self) -> None: - """Sync any per-step data needed by visualizers.""" + """Update adapted data for current simulation step.""" @abstractmethod - def get_model(self): - """Return a physics-backend model object, if applicable.""" + def get_newton_model(self) -> Any | None: + """Get Newton Model.""" @abstractmethod - def get_state(self): - """Return a physics-backend state object, if applicable.""" + def get_newton_state(self) -> Any | None: + """Get Newton State.""" + + @abstractmethod + def get_usd_stage(self) -> Any | None: + """Get USD stage.""" @abstractmethod def get_metadata(self) -> dict[str, Any]: - """Return basic metadata about the scene/backend.""" + """Get provider metadata and performance hints.""" @abstractmethod def get_transforms(self) -> dict[str, Any] | None: - """Return transform data keyed by semantic names.""" + """Get world-space transforms in backend-agnostic format.""" def get_velocities(self) -> dict[str, Any] | None: - """Return velocity data keyed by semantic names.""" - # TODO: Populate linear/angular velocities once available per backend. + """Get velocities in backend-agnostic format.""" return None def get_contacts(self) -> dict[str, Any] | None: - """Return contact data keyed by semantic names.""" - # TODO: Populate contact data once available per backend. + """Get contact data in backend-agnostic format.""" return None - def get_meshes(self) -> dict[str, Any] | None: - """Return mesh/material data keyed by semantic names.""" - # TODO: Populate mesh/material data once available per backend. + def get_mesh_data(self) -> dict[str, Any] | None: + """Get mesh geometry and materials.""" return None class SceneDataProvider: - """Facade that selects the correct scene data provider for the active backend.""" + """Facade that creates appropriate provider based on physics backend.""" def __init__( self, @@ -73,30 +79,33 @@ def __init__( self._provider = NewtonSceneDataProvider(visualizer_cfgs) elif backend == "omni": if stage is None or simulation_context is None: - logger.warning( - "Omni scene data provider requires stage and simulation context; skipping initialization." - ) + logger.warning("OV scene data provider requires stage and simulation context.") self._provider = None else: - from .ov_scene_data_provider import OmniSceneDataProvider + from .ov_scene_data_provider import OVSceneDataProvider - self._provider = OmniSceneDataProvider(visualizer_cfgs, stage, simulation_context) + self._provider = OVSceneDataProvider(visualizer_cfgs, stage, simulation_context) else: - logger.warning(f"Unknown physics backend '{backend}'. No scene data provider created.") + logger.warning(f"Unknown physics backend '{backend}'.") def update(self) -> None: if self._provider is not None: self._provider.update() - def get_model(self): + def get_newton_model(self) -> Any | None: + if self._provider is None: + return None + return self._provider.get_newton_model() + + def get_newton_state(self) -> Any | None: if self._provider is None: return None - return self._provider.get_model() + return self._provider.get_newton_state() - def get_state(self): + def get_usd_stage(self) -> Any | None: if self._provider is None: return None - return self._provider.get_state() + return self._provider.get_usd_stage() def get_metadata(self) -> dict[str, Any]: if self._provider is None: @@ -118,7 +127,7 @@ def get_contacts(self) -> dict[str, Any] | None: return None return self._provider.get_contacts() - def get_meshes(self) -> dict[str, Any] | None: + def get_mesh_data(self) -> dict[str, Any] | None: if self._provider is None: return None - return self._provider.get_meshes() + return self._provider.get_mesh_data() \ No newline at end of file diff --git a/source/isaaclab/isaaclab/sim/simulation_context.py b/source/isaaclab/isaaclab/sim/simulation_context.py index 96c4896db3b..c79aba921e4 100644 --- a/source/isaaclab/isaaclab/sim/simulation_context.py +++ b/source/isaaclab/isaaclab/sim/simulation_context.py @@ -276,8 +276,13 @@ def _init_visualizers(self) -> None: try: visualizer = cfg.create_visualizer() scene_data: dict[str, Any] = {"scene_data_provider": self._scene_data_provider} + + # OV visualizer gets USD stage and simulation context. if cfg.visualizer_type == "omniverse": - scene_data["usd_stage"] = self.stage + if self._scene_data_provider: + scene_data["usd_stage"] = self._scene_data_provider.get_usd_stage() + else: + scene_data["usd_stage"] = self.stage scene_data["simulation_context"] = self visualizer.initialize(scene_data) diff --git a/source/isaaclab/isaaclab/visualizers/newton_visualizer.py b/source/isaaclab/isaaclab/visualizers/newton_visualizer.py index b3c01fedb8a..719331a31dc 100644 --- a/source/isaaclab/isaaclab/visualizers/newton_visualizer.py +++ b/source/isaaclab/isaaclab/visualizers/newton_visualizer.py @@ -160,8 +160,8 @@ def _render_left_panel(self): changed, self.renderer.draw_wireframe = imgui.checkbox("Wireframe", self.renderer.draw_wireframe) changed, self.renderer._light_color = imgui.color_edit3("Light Color", self.renderer._light_color) - changed, self.renderer.sky_upper = imgui.color_edit3("Sky Color", self.renderer.sky_upper) - changed, self.renderer.sky_lower = imgui.color_edit3("Ground Color", self.renderer.sky_lower) + changed, self.renderer.sky_upper = imgui.color_edit3("Upper Sky Color", self.renderer.sky_upper) + changed, self.renderer.sky_lower = imgui.color_edit3("Lower Sky Color", self.renderer.sky_lower) imgui.set_next_item_open(True, imgui.Cond_.appearing) if imgui.collapsing_header("Camera"): @@ -213,8 +213,8 @@ def initialize(self, scene_data: dict[str, Any] | None = None) -> None: metadata = {} if self._scene_data_provider: - self._model = self._scene_data_provider.get_model() - self._state = self._scene_data_provider.get_state() + self._model = self._scene_data_provider.get_newton_model() + self._state = self._scene_data_provider.get_newton_state() metadata = self._scene_data_provider.get_metadata() else: try: @@ -268,8 +268,8 @@ def initialize(self, scene_data: dict[str, Any] | None = None) -> None: self._viewer.renderer.draw_sky = self.cfg.enable_sky self._viewer.renderer.draw_wireframe = self.cfg.enable_wireframe - self._viewer.renderer.sky_upper = self.cfg.background_color - self._viewer.renderer.sky_lower = self.cfg.ground_color + self._viewer.renderer.sky_upper = self.cfg.sky_upper_color + self._viewer.renderer.sky_lower = self.cfg.sky_lower_color self._viewer.renderer._light_color = self.cfg.light_color self._is_initialized = True @@ -281,13 +281,23 @@ def step(self, dt: float, state: Any | None = None) -> None: self._sim_time += dt self._step_counter += 1 + contacts = None + contacts_data = None if self._scene_data_provider: - self._state = self._scene_data_provider.get_state() + self._state = self._scene_data_provider.get_newton_state() + if self._viewer.show_contacts: + contacts_data = self._scene_data_provider.get_contacts() + if isinstance(contacts_data, dict): + contacts = contacts_data.get("contacts", contacts_data) + else: + contacts = contacts_data else: try: from isaaclab.sim._impl.newton_manager import NewtonManager self._state = NewtonManager._state_0 + if self._viewer.show_contacts: + contacts = NewtonManager._contacts except Exception: self._state = None @@ -300,6 +310,11 @@ def step(self, dt: float, state: Any | None = None) -> None: self._viewer.begin_frame(self._sim_time) if self._state is not None: self._viewer.log_state(self._state) + if contacts is not None and hasattr(self._viewer, "log_contacts"): + try: + self._viewer.log_contacts(contacts, self._state) + except Exception as exc: + logger.debug(f"[NewtonVisualizer] Failed to log contacts: {exc}") self._viewer.end_frame() else: self._viewer._update() diff --git a/source/isaaclab/isaaclab/visualizers/newton_visualizer_cfg.py b/source/isaaclab/isaaclab/visualizers/newton_visualizer_cfg.py index 0465c43ba6b..0d0439843b7 100644 --- a/source/isaaclab/isaaclab/visualizers/newton_visualizer_cfg.py +++ b/source/isaaclab/isaaclab/visualizers/newton_visualizer_cfg.py @@ -47,11 +47,11 @@ class NewtonVisualizerCfg(VisualizerCfg): enable_wireframe: bool = False """Enable wireframe rendering.""" - background_color: tuple[float, float, float] = (0.53, 0.81, 0.92) - """Background/sky color RGB [0,1].""" + sky_upper_color: tuple[float, float, float] = (0.2, 0.4, 0.6) + """Sky upper color RGB [0,1].""" - ground_color: tuple[float, float, float] = (0.18, 0.20, 0.25) - """Ground color RGB [0,1].""" + sky_lower_color: tuple[float, float, float] = (0.5, 0.6, 0.7) + """Sky lower color RGB [0,1].""" light_color: tuple[float, float, float] = (1.0, 1.0, 1.0) """Light color RGB [0,1].""" diff --git a/source/isaaclab/isaaclab/visualizers/ov_visualizer.py b/source/isaaclab/isaaclab/visualizers/ov_visualizer.py index cd16c203ea9..97b64adc9b8 100644 --- a/source/isaaclab/isaaclab/visualizers/ov_visualizer.py +++ b/source/isaaclab/isaaclab/visualizers/ov_visualizer.py @@ -39,23 +39,20 @@ def initialize(self, scene_data: dict[str, Any] | None = None) -> None: return usd_stage = None - simulation_context = None + scene_data_provider = None if scene_data is not None: usd_stage = scene_data.get("usd_stage") - simulation_context = scene_data.get("simulation_context") + scene_data_provider = scene_data.get("scene_data_provider") if usd_stage is None: raise RuntimeError("OV visualizer requires a USD stage.") metadata = {} - if simulation_context is not None: - num_envs = 0 - if hasattr(simulation_context, "scene") and simulation_context.scene is not None: - if hasattr(simulation_context.scene, "num_envs"): - num_envs = simulation_context.scene.num_envs - + if scene_data_provider is not None: + metadata = scene_data_provider.get_metadata() + else: metadata = { - "num_envs": num_envs, + "num_envs": 0, "physics_backend": "omni", "env_prim_pattern": "/World/envs/env_{}", } diff --git a/source/isaaclab/isaaclab/visualizers/rerun_visualizer.py b/source/isaaclab/isaaclab/visualizers/rerun_visualizer.py index f75555096cc..a56f4581654 100644 --- a/source/isaaclab/isaaclab/visualizers/rerun_visualizer.py +++ b/source/isaaclab/isaaclab/visualizers/rerun_visualizer.py @@ -93,8 +93,8 @@ def initialize(self, scene_data: dict[str, Any] | None = None) -> None: metadata = {} if self._scene_data_provider: - self._model = self._scene_data_provider.get_model() - self._state = self._scene_data_provider.get_state() + self._model = self._scene_data_provider.get_newton_model() + self._state = self._scene_data_provider.get_newton_state() metadata = self._scene_data_provider.get_metadata() else: try: @@ -171,7 +171,7 @@ def step(self, dt: float, state: Any | None = None) -> None: return if self._scene_data_provider: - self._state = self._scene_data_provider.get_state() + self._state = self._scene_data_provider.get_newton_state() else: try: from isaaclab.sim._impl.newton_manager import NewtonManager diff --git a/source/isaaclab/setup.py b/source/isaaclab/setup.py index 7ad8cd8ce24..c8a68b01797 100644 --- a/source/isaaclab/setup.py +++ b/source/isaaclab/setup.py @@ -33,14 +33,16 @@ # image processing "transformers==4.57.6", "einops", # needed for transformers, doesn't always auto-install - "warp-lang==1.11.0.dev20251205", + "warp-lang>=1.11.0.dev20251205", # newton visualizers / backend dependencies "mujoco>=3.4.0.dev839962392", - "mujoco-warp@ git+https://github.com/google-deepmind/mujoco_warp.git@e9a67538f2c14486121635074c5a5fd6ca55fa83", - "newton@ git+https://github.com/newton-physics/newton.git@beta-0.2.1", - "imgui-bundle==1.92.0", + "mujoco-warp>=0.0.1", + "cbor2>=5.7.0", + "newton>=0.2.1", + "imgui-bundle>=1.92.0", "PyOpenGL-accelerate==3.1.10", "matplotlib>=3.10.3", # minimum version for Python 3.12 support + "rerun-sdk>=0.27.1", # make sure this is consistent with isaac sim version "pillow==12.0.0", # livestream From f3ef06aafc88481373021d7245bad29ab5560d5b Mon Sep 17 00:00:00 2001 From: Matthew Trepte Date: Tue, 27 Jan 2026 18:16:30 +0000 Subject: [PATCH 31/46] simplify --- .../newton_scene_data_provider.py | 4 +- .../ov_scene_data_provider.py | 4 +- .../scene_data_provider.py | 52 ++----------------- 3 files changed, 5 insertions(+), 55 deletions(-) diff --git a/source/isaaclab/isaaclab/sim/scene_data_providers/newton_scene_data_provider.py b/source/isaaclab/isaaclab/sim/scene_data_providers/newton_scene_data_provider.py index 7144b599b3a..bbeb4794978 100644 --- a/source/isaaclab/isaaclab/sim/scene_data_providers/newton_scene_data_provider.py +++ b/source/isaaclab/isaaclab/sim/scene_data_providers/newton_scene_data_provider.py @@ -11,12 +11,10 @@ import logging from typing import Any -from .scene_data_provider import SceneDataProviderBase - logger = logging.getLogger(__name__) -class NewtonSceneDataProvider(SceneDataProviderBase): +class NewtonSceneDataProvider: """Scene data provider for Newton Warp physics backend. Native (cheap): Newton Model/State from NewtonManager diff --git a/source/isaaclab/isaaclab/sim/scene_data_providers/ov_scene_data_provider.py b/source/isaaclab/isaaclab/sim/scene_data_providers/ov_scene_data_provider.py index 462421d4073..a6e6e7c4050 100644 --- a/source/isaaclab/isaaclab/sim/scene_data_providers/ov_scene_data_provider.py +++ b/source/isaaclab/isaaclab/sim/scene_data_providers/ov_scene_data_provider.py @@ -13,12 +13,10 @@ import re from typing import Any -from .scene_data_provider import SceneDataProviderBase - logger = logging.getLogger(__name__) -class OVSceneDataProvider(SceneDataProviderBase): +class OVSceneDataProvider: """Scene data provider for Omni PhysX physics backend. Native (cheap): USD stage, PhysX transforms/velocities/contacts diff --git a/source/isaaclab/isaaclab/sim/scene_data_providers/scene_data_provider.py b/source/isaaclab/isaaclab/sim/scene_data_providers/scene_data_provider.py index dae8ee5c468..a5cebf10e48 100644 --- a/source/isaaclab/isaaclab/sim/scene_data_providers/scene_data_provider.py +++ b/source/isaaclab/isaaclab/sim/scene_data_providers/scene_data_provider.py @@ -4,64 +4,18 @@ # # SPDX-License-Identifier: BSD-3-Clause -"""Scene data provider abstraction for visualizers and renderers.""" +"""Scene data provider for visualizers and renderers.""" from __future__ import annotations import logging -from abc import ABC, abstractmethod from typing import Any logger = logging.getLogger(__name__) -class SceneDataProviderBase(ABC): - """Base interface for scene data providers. - - Provides simulation data in multiple formats for visualizers, renderers, - and other downstream consumers. Each backend provider implements this interface, - exposing native data cheaply and adapted data when needed. - """ - - @abstractmethod - def update(self) -> None: - """Update adapted data for current simulation step.""" - - @abstractmethod - def get_newton_model(self) -> Any | None: - """Get Newton Model.""" - - @abstractmethod - def get_newton_state(self) -> Any | None: - """Get Newton State.""" - - @abstractmethod - def get_usd_stage(self) -> Any | None: - """Get USD stage.""" - - @abstractmethod - def get_metadata(self) -> dict[str, Any]: - """Get provider metadata and performance hints.""" - - @abstractmethod - def get_transforms(self) -> dict[str, Any] | None: - """Get world-space transforms in backend-agnostic format.""" - - def get_velocities(self) -> dict[str, Any] | None: - """Get velocities in backend-agnostic format.""" - return None - - def get_contacts(self) -> dict[str, Any] | None: - """Get contact data in backend-agnostic format.""" - return None - - def get_mesh_data(self) -> dict[str, Any] | None: - """Get mesh geometry and materials.""" - return None - - class SceneDataProvider: - """Facade that creates appropriate provider based on physics backend.""" + """Creates appropriate data provider based on physics backend.""" def __init__( self, @@ -71,7 +25,7 @@ def __init__( simulation_context=None, ) -> None: self._backend = backend - self._provider: SceneDataProviderBase | None = None + self._provider = None if backend == "newton": from .newton_scene_data_provider import NewtonSceneDataProvider From 550ced3fa7defc049c2f675b05d6d7f39f930d7f Mon Sep 17 00:00:00 2001 From: Matthew Trepte Date: Tue, 27 Jan 2026 18:18:20 +0000 Subject: [PATCH 32/46] correction --- .../isaaclab/isaaclab/sim/scene_data_providers/__init__.py | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/source/isaaclab/isaaclab/sim/scene_data_providers/__init__.py b/source/isaaclab/isaaclab/sim/scene_data_providers/__init__.py index 55ccb14863c..79d7bff100c 100644 --- a/source/isaaclab/isaaclab/sim/scene_data_providers/__init__.py +++ b/source/isaaclab/isaaclab/sim/scene_data_providers/__init__.py @@ -6,13 +6,12 @@ """Scene data providers for visualizers and renderers.""" -from .scene_data_provider import SceneDataProvider, SceneDataProviderBase from .newton_scene_data_provider import NewtonSceneDataProvider -from .ov_scene_data_provider import OmniSceneDataProvider +from .ov_scene_data_provider import OVSceneDataProvider +from .scene_data_provider import SceneDataProvider __all__ = [ "SceneDataProvider", - "SceneDataProviderBase", "NewtonSceneDataProvider", - "OmniSceneDataProvider", + "OVSceneDataProvider", ] From a69482b409a2946d6abf0579e7c6a375179fc9f9 Mon Sep 17 00:00:00 2001 From: Matthew Trepte Date: Tue, 27 Jan 2026 19:04:21 +0000 Subject: [PATCH 33/46] clean --- source/isaaclab/isaaclab/utils/__init__.py | 1 - .../isaaclab/utils/simulation_runner.py | 37 ------------------- 2 files changed, 38 deletions(-) delete mode 100644 source/isaaclab/isaaclab/utils/simulation_runner.py diff --git a/source/isaaclab/isaaclab/utils/__init__.py b/source/isaaclab/isaaclab/utils/__init__.py index 5dc6e92da58..1295715857f 100644 --- a/source/isaaclab/isaaclab/utils/__init__.py +++ b/source/isaaclab/isaaclab/utils/__init__.py @@ -13,7 +13,6 @@ from .logger import * from .mesh import * from .modifiers import * -from .simulation_runner import close_simulation, is_simulation_running from .string import * from .timer import Timer from .types import * diff --git a/source/isaaclab/isaaclab/utils/simulation_runner.py b/source/isaaclab/isaaclab/utils/simulation_runner.py deleted file mode 100644 index 1b0b89a031e..00000000000 --- a/source/isaaclab/isaaclab/utils/simulation_runner.py +++ /dev/null @@ -1,37 +0,0 @@ -# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). -# All rights reserved. -# -# SPDX-License-Identifier: BSD-3-Clause - -"""Utility functions for running simulation loops with visualizer-agnostic is_running checks.""" - -from __future__ import annotations - -from typing import TYPE_CHECKING, Any - -if TYPE_CHECKING: - from isaaclab.sim import SimulationContext - - -def is_simulation_running(simulation_app: Any | None, sim_context: SimulationContext | None = None) -> bool: - """Check if the simulation should continue running. - - - Omniverse mode: delegates to SimulationApp.is_running() - - Standalone mode with visualizers: checks if any visualizer window is still open - - Headless mode (no visualizers): always returns True (use Ctrl+C or break to exit) - """ - if simulation_app is not None: - return simulation_app.is_running() - - if sim_context is not None and hasattr(sim_context, "_visualizers"): - visualizers = sim_context._visualizers - if visualizers: - return any(v.is_running() for v in visualizers) - - return True - - -def close_simulation(simulation_app: Any | None) -> None: - """Close the simulation app if running in Omniverse mode.""" - if simulation_app is not None: - simulation_app.close() From 3728ac0b66a3d79ccd5f2a36a6268f725f7c4b29 Mon Sep 17 00:00:00 2001 From: Matthew Trepte Date: Tue, 27 Jan 2026 19:05:27 +0000 Subject: [PATCH 34/46] rm files --- .../spawners/materials/visual_materials.py | 173 ++++++++++++++++++ 1 file changed, 173 insertions(+) diff --git a/source/isaaclab/isaaclab/sim/spawners/materials/visual_materials.py b/source/isaaclab/isaaclab/sim/spawners/materials/visual_materials.py index 713ce34749b..ab1283c9852 100644 --- a/source/isaaclab/isaaclab/sim/spawners/materials/visual_materials.py +++ b/source/isaaclab/isaaclab/sim/spawners/materials/visual_materials.py @@ -111,6 +111,179 @@ def spawn_preview_surface(prim_path: str, cfg: visual_materials_cfg.PreviewSurfa return prim +@clone +def spawn_from_mdl_file( + prim_path: str, cfg: visual_materials_cfg.MdlFileCfg | visual_materials_cfg.GlassMdlCfg +) -> Usd.Prim: + """Load a material from its MDL file and override the settings with the given config. + + NVIDIA's `Material Definition Language (MDL) `__ + is a language for defining physically-based materials. The MDL file format is a binary format + that can be loaded by Omniverse and other applications such as Adobe Substance Designer. + To learn more about MDL, see the `documentation `_. + + The function calls the USD command `CreateMdlMaterialPrim`_ to create the prim. + + .. _CreateMdlMaterialPrim: https://docs.omniverse.nvidia.com/kit/docs/omni.usd/latest/omni.usd.commands/omni.usd.commands.CreateMdlMaterialPrimCommand.html + + .. note:: + This function is decorated with :func:`clone` that resolves prim path into list of paths + if the input prim path is a regex pattern. This is done to support spawning multiple assets + from a single and cloning the USD prim at the given path expression. + + Args: + prim_path: The prim path or pattern to spawn the asset at. If the prim path is a regex pattern, + then the asset is spawned at all the matching prim paths. + cfg: The configuration instance. + + Returns: + The created prim. + + Raises: + ValueError: If a prim already exists at the given path. + """ + # get stage handle + stage = get_current_stage() + + # spawn material if it doesn't exist. + if not stage.GetPrimAtPath(prim_path).IsValid(): + # extract material name from path + material_name = cfg.mdl_path.split("/")[-1].split(".")[0] + CreateMdlMaterialPrimCommand( + mtl_url=cfg.mdl_path.format(NVIDIA_NUCLEUS_DIR=NVIDIA_NUCLEUS_DIR), + mtl_name=material_name, + mtl_path=prim_path, + stage=stage, + select_new_prim=False, + ).do() + else: + raise ValueError(f"A prim already exists at path: '{prim_path}'.") + # obtain prim + prim = stage.GetPrimAtPath(f"{prim_path}/Shader") + # check prim is valid + if not prim.IsValid(): + raise ValueError(f"Failed to create MDL material at path: '{prim_path}'.") + # apply properties + cfg = cfg.to_dict() # type: ignore + del cfg["func"] + del cfg["mdl_path"] + for attr_name, attr_value in cfg.items(): + safe_set_attribute_on_usd_prim(prim, f"inputs:{attr_name}", attr_value, camel_case=False) + # return prim + return prim +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +from __future__ import annotations + +import logging +from typing import TYPE_CHECKING + +from omni.usd.commands import CreateMdlMaterialPrimCommand, CreateShaderPrimFromSdrCommand +from pxr import Usd, UsdShade + +from isaaclab.sim.utils import clone, safe_set_attribute_on_usd_prim +from isaaclab.sim.utils.stage import get_current_stage +from isaaclab.utils.assets import NVIDIA_NUCLEUS_DIR + +if TYPE_CHECKING: + from . import visual_materials_cfg + +# import logger +logger = logging.getLogger(__name__) + + +@clone +def spawn_preview_surface(prim_path: str, cfg: visual_materials_cfg.PreviewSurfaceCfg) -> Usd.Prim: + """Create a preview surface prim and override the settings with the given config. + + A preview surface is a physically-based surface that handles simple shaders while supporting + both *specular* and *metallic* workflows. All color inputs are in linear color space (RGB). + For more information, see the `documentation `__. + + The function calls the USD command `CreateShaderPrimFromSdrCommand`_ to create the prim. + + .. _CreateShaderPrimFromSdrCommand: https://docs.omniverse.nvidia.com/kit/docs/omni.usd/latest/omni.usd.commands/omni.usd.commands.CreateShaderPrimFromSdrCommand.html + + .. note:: + This function is decorated with :func:`clone` that resolves prim path into list of paths + if the input prim path is a regex pattern. This is done to support spawning multiple assets + from a single and cloning the USD prim at the given path expression. + + Args: + prim_path: The prim path or pattern to spawn the asset at. If the prim path is a regex pattern, + then the asset is spawned at all the matching prim paths. + cfg: The configuration instance. + + Returns: + The created prim. + + Raises: + ValueError: If a prim already exists at the given path. + """ + # get stage handle + stage = get_current_stage() + + # spawn material if it doesn't exist. + if not stage.GetPrimAtPath(prim_path).IsValid(): + # note: we don't use Omniverse's CreatePreviewSurfaceMaterialPrimCommand + # since it does not support USD stage as an argument. The created material + # in that case is always the one from USD Context which makes it difficult to + # handle scene creation on a custom stage. + material_prim = UsdShade.Material.Define(stage, prim_path) + if material_prim: + try: + shader_prim = CreateShaderPrimFromSdrCommand( + parent_path=prim_path, + identifier="UsdPreviewSurface", + stage_or_context=stage, + name="Shader", + ).do() + except TypeError: + shader_prim = CreateShaderPrimFromSdrCommand( + parent_path=prim_path, + identifier="UsdPreviewSurface", + stage_or_context=stage, + ).do() + # bind the shader graph to the material + if shader_prim: + surface_out = shader_prim.GetOutput("surface") + if surface_out: + material_prim.CreateSurfaceOutput().ConnectToSource(surface_out) + + displacement_out = shader_prim.GetOutput("displacement") + if displacement_out: + material_prim.CreateDisplacementOutput().ConnectToSource(displacement_out) + else: + raise ValueError(f"Failed to create preview surface shader at path: '{prim_path}'.") + else: + raise ValueError(f"A prim already exists at path: '{prim_path}'.") + + # obtain prim + prim = None + if shader_prim: + if hasattr(shader_prim, "GetPrim"): + prim = shader_prim.GetPrim() + elif hasattr(shader_prim, "IsValid"): + prim = shader_prim + elif hasattr(shader_prim, "GetPath"): + prim = stage.GetPrimAtPath(str(shader_prim.GetPath())) + if prim is None or not prim.IsValid(): + prim = stage.GetPrimAtPath(f"{prim_path}/Shader") + # check prim is valid + if not prim.IsValid(): + raise ValueError(f"Failed to create preview surface material at path: '{prim_path}'.") + # apply properties + cfg = cfg.to_dict() # type: ignore + del cfg["func"] + for attr_name, attr_value in cfg.items(): + safe_set_attribute_on_usd_prim(prim, f"inputs:{attr_name}", attr_value, camel_case=True) + + return prim + + @clone def spawn_from_mdl_file( prim_path: str, cfg: visual_materials_cfg.MdlFileCfg | visual_materials_cfg.GlassMdlCfg From ddf646abc9a0b25ab741808d42ae08277ff0f684 Mon Sep 17 00:00:00 2001 From: Matthew Trepte Date: Tue, 27 Jan 2026 19:09:43 +0000 Subject: [PATCH 35/46] revert file --- source/isaaclab/isaaclab/envs/manager_based_env.py | 8 -------- 1 file changed, 8 deletions(-) diff --git a/source/isaaclab/isaaclab/envs/manager_based_env.py b/source/isaaclab/isaaclab/envs/manager_based_env.py index a4eda256acd..4162b46ad77 100644 --- a/source/isaaclab/isaaclab/envs/manager_based_env.py +++ b/source/isaaclab/isaaclab/envs/manager_based_env.py @@ -140,14 +140,6 @@ def __init__(self, cfg: ManagerBasedEnvCfg): self.scene = InteractiveScene(self.cfg.scene) attach_stage_to_usd_context() print("[INFO]: Scene manager: ", self.scene) - from isaaclab.sim.utils import find_matching_prim_paths - - env_prim_paths = find_matching_prim_paths("/World/envs/env_.*", stage=self.scene.stage) - print( - "[SceneDebug] env prims after InteractiveScene: " - f"num_envs_setting={self.cfg.scene.num_envs}, env_prims={len(env_prim_paths)}" - ) - # import ipdb; ipdb.set_trace() # set up camera viewport controller # viewport is not available in other rendering modes so the function will throw a warning From 79ecb5b022123451a2bb53b359df48a1b89a73b3 Mon Sep 17 00:00:00 2001 From: Matthew Trepte Date: Tue, 27 Jan 2026 21:39:54 +0000 Subject: [PATCH 36/46] fixes + rm contact debug --- .../isaaclab/scene/interactive_scene.py | 1 - .../ov_scene_data_provider.py | 156 +--------- .../spawners/materials/visual_materials.py | 1 - .../isaaclab/visualizers/newton_visualizer.py | 58 +--- .../isaaclab/visualizers/ov_visualizer.py | 267 +++++++----------- .../isaaclab/visualizers/rerun_visualizer.py | 77 +---- .../isaaclab/visualizers/visualizer_cfg.py | 10 +- 7 files changed, 131 insertions(+), 439 deletions(-) diff --git a/source/isaaclab/isaaclab/scene/interactive_scene.py b/source/isaaclab/isaaclab/scene/interactive_scene.py index 96353d719a8..8fb903113c6 100644 --- a/source/isaaclab/isaaclab/scene/interactive_scene.py +++ b/source/isaaclab/isaaclab/scene/interactive_scene.py @@ -126,7 +126,6 @@ def __init__(self, cfg: InteractiveSceneCfg): # TODO(mtrepte): remove self.cfg.clone_in_fabric = False - # initialize scene elements self._terrain = None self._articulations = dict() diff --git a/source/isaaclab/isaaclab/sim/scene_data_providers/ov_scene_data_provider.py b/source/isaaclab/isaaclab/sim/scene_data_providers/ov_scene_data_provider.py index a6e6e7c4050..3a6f1b57ca9 100644 --- a/source/isaaclab/isaaclab/sim/scene_data_providers/ov_scene_data_provider.py +++ b/source/isaaclab/isaaclab/sim/scene_data_providers/ov_scene_data_provider.py @@ -19,7 +19,7 @@ class OVSceneDataProvider: """Scene data provider for Omni PhysX physics backend. - Native (cheap): USD stage, PhysX transforms/velocities/contacts + Native (cheap): USD stage, PhysX transforms/velocities Adapted (expensive): Newton Model/State (built from USD, synced each step) Performance: Only builds Newton data if Newton/Rerun visualizers are active. @@ -34,7 +34,6 @@ def __init__(self, visualizer_cfgs: list[Any] | None, stage, simulation_context) self._physics_sim_view = SimulationManager.get_physics_sim_view() self._rigid_body_view = None self._articulation_view = None - self._contact_view = None self._xform_views: dict[str, Any] = {} self._body_key_index_map: dict[str, int] = {} self._view_body_index_map: dict[str, list[int]] = {} @@ -75,6 +74,7 @@ def __init__(self, visualizer_cfgs: list[Any] | None, stage, simulation_context) logger.info("[OVSceneDataProvider] OV visualizer only - skipping Newton model build") def _get_num_envs(self) -> int: + # TODO(mtrepte): is there a better way to get num_envs? try: import carb @@ -135,7 +135,6 @@ def _build_newton_model_from_usd(self) -> None: self._newton_state = self._newton_model.state() self._rigid_body_paths = list(self._newton_model.body_key) self._xform_views.clear() - self._contact_view = None self._body_key_index_map = {path: i for i, path in enumerate(self._rigid_body_paths)} self._view_body_index_map = {} except ModuleNotFoundError as exc: @@ -187,6 +186,7 @@ def _setup_articulation_view(self) -> None: self._articulation_view = None def _get_view_world_poses(self, view): + # TODO(mtrepte): this can be revisited & simplifiedafter the function naming gets unified if view is None: return None, None @@ -271,146 +271,6 @@ def _get_view_velocities(self, view): return None, None - def _setup_contact_view(self) -> None: - if not self._rigid_body_paths or self._contact_view is not None: - return - try: - from pxr import PhysxSchema - - contact_paths = [ - path - for path in self._rigid_body_paths - if self._stage.GetPrimAtPath(path).HasAPI(PhysxSchema.PhysxContactReportAPI) - ] - if contact_paths: - contact_paths = self._wildcard_env_paths(contact_paths) - self._contact_view = self._physics_sim_view.create_rigid_contact_view(contact_paths) - except Exception as exc: - logger.debug(f"[SceneDataProvider] Failed to create ContactView: {exc}") - self._contact_view = None - - def _get_view_contacts(self, view): - if view is None: - return None - dt = getattr(self._simulation_context, "cfg", None) - dt = getattr(dt, "dt", 1.0 / 60.0) if dt is not None else 1.0 / 60.0 - - try: - num_envs = int(self._metadata.get("num_envs") or 1) - view_count = getattr(view, "count", 0) - num_bodies = view_count // num_envs if num_envs > 0 and view_count else 0 - num_filters = getattr(view, "filter_count", 0) - - output: dict[str, Any] = {} - - method = getattr(view, "get_net_contact_forces", None) - if method is not None: - output["net_forces_w"] = method(dt=dt) - - method = getattr(view, "get_contact_data", None) - if method is not None: - data = method(dt=dt) - if isinstance(data, tuple) and len(data) >= 6: - _, contact_points, contact_normals, contact_distances, buffer_count, buffer_start_indices = data[:6] - if num_envs > 0 and num_bodies > 0 and num_filters > 0: - output["contact_points_w"] = self._unpack_contact_buffer_data( - contact_points, - buffer_count, - buffer_start_indices, - num_envs, - num_bodies, - num_filters, - avg=True, - default=float("nan"), - ) - output["contact_normals_w"] = self._unpack_contact_buffer_data( - contact_normals, - buffer_count, - buffer_start_indices, - num_envs, - num_bodies, - num_filters, - avg=True, - default=float("nan"), - ) - output["contact_distances"] = self._unpack_contact_buffer_data( - contact_distances.view(-1, 1), - buffer_count, - buffer_start_indices, - num_envs, - num_bodies, - num_filters, - avg=True, - default=float("nan"), - ).squeeze(-1) - - method = getattr(view, "get_friction_data", None) - if method is not None: - data = method(dt=dt) - if isinstance(data, tuple) and len(data) >= 4: - friction_forces, _, buffer_count, buffer_start_indices = data[:4] - if num_envs > 0 and num_bodies > 0 and num_filters > 0: - output["friction_forces_w"] = self._unpack_contact_buffer_data( - friction_forces, - buffer_count, - buffer_start_indices, - num_envs, - num_bodies, - num_filters, - avg=False, - default=0.0, - ) - - if not output: - return None - return output - except Exception as exc: - logger.debug(f"[SceneDataProvider] Failed to read ContactView data: {exc}") - return None - - def _unpack_contact_buffer_data( - self, - contact_data, - buffer_count, - buffer_start_indices, - num_envs: int, - num_bodies: int, - num_filters: int, - avg: bool = True, - default: float = float("nan"), - ): - try: - import torch - - if num_envs <= 0 or num_bodies <= 0 or num_filters <= 0: - return None - - counts = buffer_count.view(-1) - starts = buffer_start_indices.view(-1) - n_rows = counts.numel() - if contact_data is None or n_rows == 0: - return None - - data = contact_data - if data.ndim == 1: - data = data.view(-1, 1) - dim = data.shape[-1] - - agg = torch.full((n_rows, dim), default, device=data.device, dtype=data.dtype) - total = int(counts.sum().item()) - if total > 0: - row_ids = torch.repeat_interleave(torch.arange(n_rows, device=data.device), counts) - block_starts = counts.cumsum(0) - counts - deltas = torch.arange(row_ids.numel(), device=data.device) - block_starts.repeat_interleave(counts) - flat_idx = starts[row_ids] + deltas - pts = data.index_select(0, flat_idx) - agg = agg.zero_().index_add_(0, row_ids, pts) - agg = agg / counts.clamp_min(1).unsqueeze(-1) if avg else agg - agg[counts == 0] = default - - return agg.view(num_envs, num_bodies, num_filters, dim) - except Exception: - return None def _get_xform_world_poses(self): if not self._rigid_body_paths: @@ -525,7 +385,6 @@ def update(self) -> None: # Future extensions: # - Populate velocities into self._newton_state.body_qd - # - Sync contacts into Newton Contacts for richer debug visualizations # - Cache mesh/material data for Rerun/renderer integrations except Exception as exc: logger.debug(f"[SceneDataProvider] Failed to sync Omni transforms to Newton state: {exc}") @@ -580,10 +439,5 @@ def get_velocities(self) -> dict[str, Any] | None: return None def get_contacts(self) -> dict[str, Any] | None: - if self._contact_view is None: - self._setup_contact_view() - data = self._get_view_contacts(self._contact_view) - if data is None: - return None - data["source"] = "contact_view" - return data + """Contacts not yet supported for OV backend.""" + return None diff --git a/source/isaaclab/isaaclab/sim/spawners/materials/visual_materials.py b/source/isaaclab/isaaclab/sim/spawners/materials/visual_materials.py index ab1283c9852..9f205952d3e 100644 --- a/source/isaaclab/isaaclab/sim/spawners/materials/visual_materials.py +++ b/source/isaaclab/isaaclab/sim/spawners/materials/visual_materials.py @@ -107,7 +107,6 @@ def spawn_preview_surface(prim_path: str, cfg: visual_materials_cfg.PreviewSurfa del cfg["func"] for attr_name, attr_value in cfg.items(): safe_set_attribute_on_usd_prim(prim, f"inputs:{attr_name}", attr_value, camel_case=True) - return prim diff --git a/source/isaaclab/isaaclab/visualizers/newton_visualizer.py b/source/isaaclab/isaaclab/visualizers/newton_visualizer.py index 719331a31dc..39c9eddf82d 100644 --- a/source/isaaclab/isaaclab/visualizers/newton_visualizer.py +++ b/source/isaaclab/isaaclab/visualizers/newton_visualizer.py @@ -208,31 +208,13 @@ def initialize(self, scene_data: dict[str, Any] | None = None) -> None: if self._is_initialized: return - if scene_data and "scene_data_provider" in scene_data: - self._scene_data_provider = scene_data["scene_data_provider"] - - metadata = {} - if self._scene_data_provider: - self._model = self._scene_data_provider.get_newton_model() - self._state = self._scene_data_provider.get_newton_state() - metadata = self._scene_data_provider.get_metadata() - else: - try: - from isaaclab.sim._impl.newton_manager import NewtonManager - - self._model = NewtonManager._model - self._state = NewtonManager._state_0 - metadata = { - "physics_backend": "newton", - "num_envs": NewtonManager._num_envs if NewtonManager._num_envs is not None else 0, - "gravity_vector": NewtonManager._gravity_vector, - "clone_physics_only": NewtonManager._clone_physics_only, - } - except Exception: - pass - - if self._model is None: - raise RuntimeError("Newton visualizer requires a Newton Model. Ensure a scene data provider is available.") + if not scene_data or "scene_data_provider" not in scene_data: + raise RuntimeError("Newton visualizer requires scene_data_provider.") + + self._scene_data_provider = scene_data["scene_data_provider"] + self._model = self._scene_data_provider.get_newton_model() + self._state = self._scene_data_provider.get_newton_state() + metadata = self._scene_data_provider.get_metadata() self._viewer = NewtonViewerGL( width=self.cfg.window_width, @@ -281,25 +263,15 @@ def step(self, dt: float, state: Any | None = None) -> None: self._sim_time += dt self._step_counter += 1 + self._state = self._scene_data_provider.get_newton_state() + contacts = None - contacts_data = None - if self._scene_data_provider: - self._state = self._scene_data_provider.get_newton_state() - if self._viewer.show_contacts: - contacts_data = self._scene_data_provider.get_contacts() - if isinstance(contacts_data, dict): - contacts = contacts_data.get("contacts", contacts_data) - else: - contacts = contacts_data - else: - try: - from isaaclab.sim._impl.newton_manager import NewtonManager - - self._state = NewtonManager._state_0 - if self._viewer.show_contacts: - contacts = NewtonManager._contacts - except Exception: - self._state = None + if self._viewer.show_contacts: + contacts_data = self._scene_data_provider.get_contacts() + if isinstance(contacts_data, dict): + contacts = contacts_data.get("contacts", contacts_data) + else: + contacts = contacts_data update_frequency = self._viewer._update_frequency if self._viewer else self._update_frequency if self._step_counter % update_frequency != 0: diff --git a/source/isaaclab/isaaclab/visualizers/ov_visualizer.py b/source/isaaclab/isaaclab/visualizers/ov_visualizer.py index 97b64adc9b8..33596629561 100644 --- a/source/isaaclab/isaaclab/visualizers/ov_visualizer.py +++ b/source/isaaclab/isaaclab/visualizers/ov_visualizer.py @@ -38,24 +38,9 @@ def initialize(self, scene_data: dict[str, Any] | None = None) -> None: logger.warning("[OVVisualizer] Already initialized.") return - usd_stage = None - scene_data_provider = None - if scene_data is not None: - usd_stage = scene_data.get("usd_stage") - scene_data_provider = scene_data.get("scene_data_provider") - - if usd_stage is None: - raise RuntimeError("OV visualizer requires a USD stage.") - - metadata = {} - if scene_data_provider is not None: - metadata = scene_data_provider.get_metadata() - else: - metadata = { - "num_envs": 0, - "physics_backend": "omni", - "env_prim_pattern": "/World/envs/env_{}", - } + usd_stage = scene_data["usd_stage"] + scene_data_provider = scene_data["scene_data_provider"] + metadata = scene_data_provider.get_metadata() self._ensure_simulation_app() self._setup_viewport(usd_stage, metadata) @@ -103,171 +88,111 @@ def set_camera_view( self._set_viewport_camera(tuple(eye), tuple(target)) def _ensure_simulation_app(self) -> None: + import omni.kit.app + + app = omni.kit.app.get_app() + if app is None or not app.is_running(): + raise RuntimeError("[OVVisualizer] Isaac Sim app is not running.") + try: - import omni.kit.app - - app = omni.kit.app.get_app() - if app is None or not app.is_running(): - raise RuntimeError( - "[OVVisualizer] No Isaac Sim app is running. " - "OV visualizer requires Isaac Sim to be launched before initialization." - ) - - try: - from isaacsim import SimulationApp - - sim_app = None - if hasattr(SimulationApp, "_instance") and SimulationApp._instance is not None: - sim_app = SimulationApp._instance - elif hasattr(SimulationApp, "instance") and callable(SimulationApp.instance): - sim_app = SimulationApp.instance() - - if sim_app is not None: - self._simulation_app = sim_app - if self._simulation_app.config.get("headless", False): - logger.warning( - "[OVVisualizer] Running in headless mode. " - "OV visualizer requires GUI mode (launch with --headless=False)." - ) - else: - logger.info("[OVVisualizer] Using existing Isaac Sim app instance.") - else: - logger.info("[OVVisualizer] Isaac Sim app is running (via omni.kit.app).") - except ImportError: - logger.info("[OVVisualizer] Using running Isaac Sim app (SimulationApp module not available).") - except ImportError as exc: - raise ImportError( - f"[OVVisualizer] Could not import omni.kit.app: {exc}. Isaac Sim may not be installed or not running." - ) + from isaacsim import SimulationApp + + sim_app = None + if hasattr(SimulationApp, "_instance") and SimulationApp._instance is not None: + sim_app = SimulationApp._instance + elif hasattr(SimulationApp, "instance") and callable(SimulationApp.instance): + sim_app = SimulationApp.instance() + + if sim_app is not None: + self._simulation_app = sim_app + if self._simulation_app.config.get("headless", False): + logger.warning("[OVVisualizer] Running in headless mode. Viewport may not display.") + except ImportError: + pass def _setup_viewport(self, usd_stage, metadata: dict) -> None: - try: - import omni.kit.viewport.utility as vp_utils - from omni.ui import DockPosition - - if self.cfg.create_viewport and self.cfg.viewport_name: - dock_position_map = { - "LEFT": DockPosition.LEFT, - "RIGHT": DockPosition.RIGHT, - "BOTTOM": DockPosition.BOTTOM, - "SAME": DockPosition.SAME, - } - dock_pos = dock_position_map.get(self.cfg.dock_position.upper(), DockPosition.SAME) - - self._viewport_window = vp_utils.create_viewport_window( - name=self.cfg.viewport_name, - width=self.cfg.window_width, - height=self.cfg.window_height, - position_x=50, - position_y=50, - docked=True, - ) - - logger.info(f"[OVVisualizer] Created viewport '{self.cfg.viewport_name}'") - asyncio.ensure_future(self._dock_viewport_async(self.cfg.viewport_name, dock_pos)) - - if self._viewport_window: - self._create_and_assign_camera(usd_stage) - else: - if self.cfg.viewport_name: - self._viewport_window = vp_utils.get_viewport_window_by_name(self.cfg.viewport_name) - if self._viewport_window is None: - logger.warning( - f"[OVVisualizer] Viewport '{self.cfg.viewport_name}' not found. Using active viewport." - ) - self._viewport_window = vp_utils.get_active_viewport_window() - else: - logger.info(f"[OVVisualizer] Using existing viewport '{self.cfg.viewport_name}'") - else: - self._viewport_window = vp_utils.get_active_viewport_window() - logger.info("[OVVisualizer] Using existing active viewport") + import omni.kit.viewport.utility as vp_utils + from omni.ui import DockPosition + + if self.cfg.create_viewport and self.cfg.viewport_name: + dock_position_map = { + "LEFT": DockPosition.LEFT, + "RIGHT": DockPosition.RIGHT, + "BOTTOM": DockPosition.BOTTOM, + "SAME": DockPosition.SAME, + } + dock_pos = dock_position_map.get(self.cfg.dock_position.upper(), DockPosition.SAME) + + self._viewport_window = vp_utils.create_viewport_window( + name=self.cfg.viewport_name, + width=self.cfg.window_width, + height=self.cfg.window_height, + position_x=50, + position_y=50, + docked=True, + ) - if self._viewport_window is None: - logger.warning("[OVVisualizer] Could not get/create viewport.") - return + logger.info(f"[OVVisualizer] Created viewport '{self.cfg.viewport_name}'") + asyncio.ensure_future(self._dock_viewport_async(self.cfg.viewport_name, dock_pos)) + self._create_and_assign_camera(usd_stage) + else: + if self.cfg.viewport_name: + self._viewport_window = vp_utils.get_viewport_window_by_name(self.cfg.viewport_name) + if self._viewport_window is None: + logger.warning(f"[OVVisualizer] Viewport '{self.cfg.viewport_name}' not found. Using active.") + self._viewport_window = vp_utils.get_active_viewport_window() + else: + self._viewport_window = vp_utils.get_active_viewport_window() - self._viewport_api = self._viewport_window.viewport_api - self._set_viewport_camera(self.cfg.camera_position, self.cfg.camera_target) - logger.info(f"[OVVisualizer] Viewport configured (size: {self.cfg.window_width}x{self.cfg.window_height})") - except ImportError as exc: - logger.warning(f"[OVVisualizer] Viewport utilities unavailable: {exc}") - except Exception as exc: - logger.error(f"[OVVisualizer] Error setting up viewport: {exc}") + self._viewport_api = self._viewport_window.viewport_api + self._set_viewport_camera(self.cfg.camera_position, self.cfg.camera_target) async def _dock_viewport_async(self, viewport_name: str, dock_position) -> None: - try: - import omni.kit.app - import omni.ui - - viewport_window = None - for i in range(10): - viewport_window = omni.ui.Workspace.get_window(viewport_name) - if viewport_window: - logger.info(f"[OVVisualizer] Found viewport window '{viewport_name}' after {i} frames") + import omni.kit.app + import omni.ui + + viewport_window = None + for _ in range(10): + viewport_window = omni.ui.Workspace.get_window(viewport_name) + if viewport_window: + break + await omni.kit.app.get_app().next_update_async() + + if not viewport_window: + logger.warning(f"[OVVisualizer] Could not find viewport window '{viewport_name}'.") + return + + main_viewport = omni.ui.Workspace.get_window("Viewport") + if not main_viewport: + for alt_name in ["/OmniverseKit/Viewport", "Viewport Next"]: + main_viewport = omni.ui.Workspace.get_window(alt_name) + if main_viewport: break - await omni.kit.app.get_app().next_update_async() - - if not viewport_window: - logger.warning(f"[OVVisualizer] Could not find viewport window '{viewport_name}' in workspace.") - return - - main_viewport = omni.ui.Workspace.get_window("Viewport") - if not main_viewport: - for alt_name in ["/OmniverseKit/Viewport", "Viewport Next"]: - main_viewport = omni.ui.Workspace.get_window(alt_name) - if main_viewport: - break - - if main_viewport and main_viewport != viewport_window: - viewport_window.dock_in(main_viewport, dock_position, 0.5) - await omni.kit.app.get_app().next_update_async() - viewport_window.focus() - viewport_window.visible = True - await omni.kit.app.get_app().next_update_async() - viewport_window.focus() - - logger.info( - f"[OVVisualizer] Docked viewport '{viewport_name}' at position {self.cfg.dock_position} and set as" - " active" - ) - else: - logger.info( - f"[OVVisualizer] Could not find main viewport for docking. Viewport '{viewport_name}' will remain" - " floating." - ) - except Exception as exc: - logger.warning(f"[OVVisualizer] Error docking viewport: {exc}") + + if main_viewport and main_viewport != viewport_window: + viewport_window.dock_in(main_viewport, dock_position, 0.5) + await omni.kit.app.get_app().next_update_async() + viewport_window.focus() + viewport_window.visible = True + await omni.kit.app.get_app().next_update_async() + viewport_window.focus() def _create_and_assign_camera(self, usd_stage) -> None: - try: - camera_path = f"/World/Cameras/{self.cfg.viewport_name}_Camera" - camera_prim = usd_stage.GetPrimAtPath(camera_path) - if not camera_prim.IsValid(): - UsdGeom.Camera.Define(usd_stage, camera_path) - logger.info(f"[OVVisualizer] Created camera: {camera_path}") - else: - logger.info(f"[OVVisualizer] Using existing camera: {camera_path}") + camera_path = f"/World/Cameras/{self.cfg.viewport_name}_Camera" + camera_prim = usd_stage.GetPrimAtPath(camera_path) + if not camera_prim.IsValid(): + UsdGeom.Camera.Define(usd_stage, camera_path) - if self._viewport_api: - self._viewport_api.set_active_camera(camera_path) - logger.info(f"[OVVisualizer] Assigned camera '{camera_path}' to viewport '{self.cfg.viewport_name}'") - except Exception as exc: - logger.warning(f"[OVVisualizer] Could not create/assign camera: {exc}. Using default camera.") + if self._viewport_api: + self._viewport_api.set_active_camera(camera_path) def _set_viewport_camera(self, position: tuple[float, float, float], target: tuple[float, float, float]) -> None: - if self._viewport_api is None: - return + import isaacsim.core.utils.viewports as vp_utils - try: - import isaacsim.core.utils.viewports as vp_utils - - camera_path = self._viewport_api.get_active_camera() - if not camera_path: - camera_path = "/OmniverseKit_Persp" + camera_path = self._viewport_api.get_active_camera() + if not camera_path: + camera_path = "/OmniverseKit_Persp" - vp_utils.set_camera_view( - eye=list(position), target=list(target), camera_prim_path=camera_path, viewport_api=self._viewport_api - ) - logger.info(f"[OVVisualizer] Camera set: pos={position}, target={target}, camera={camera_path}") - except Exception as exc: - logger.warning(f"[OVVisualizer] Could not set camera: {exc}") + vp_utils.set_camera_view( + eye=list(position), target=list(target), camera_prim_path=camera_path, viewport_api=self._viewport_api + ) diff --git a/source/isaaclab/isaaclab/visualizers/rerun_visualizer.py b/source/isaaclab/isaaclab/visualizers/rerun_visualizer.py index a56f4581654..00d2623001e 100644 --- a/source/isaaclab/isaaclab/visualizers/rerun_visualizer.py +++ b/source/isaaclab/isaaclab/visualizers/rerun_visualizer.py @@ -13,22 +13,14 @@ from .rerun_visualizer_cfg import RerunVisualizerCfg from .visualizer import Visualizer -logger = logging.getLogger(__name__) - -try: - import rerun as rr - import rerun.blueprint as rrb - from newton.viewer import ViewerRerun +import rerun as rr +import rerun.blueprint as rrb +from newton.viewer import ViewerRerun - _RERUN_AVAILABLE = True -except ImportError: - rr = None - rrb = None - ViewerRerun = None - _RERUN_AVAILABLE = False +logger = logging.getLogger(__name__) -class NewtonViewerRerun(ViewerRerun if _RERUN_AVAILABLE else object): +class NewtonViewerRerun(ViewerRerun): """Isaac Lab wrapper for Newton's ViewerRerun.""" def __init__( @@ -72,10 +64,6 @@ class RerunVisualizer(Visualizer): def __init__(self, cfg: RerunVisualizerCfg): super().__init__(cfg) self.cfg: RerunVisualizerCfg = cfg - - if not _RERUN_AVAILABLE: - raise ImportError("Rerun visualizer requires rerun-sdk and Newton. Install: pip install rerun-sdk") - self._viewer: NewtonViewerRerun | None = None self._model = None self._state = None @@ -85,39 +73,16 @@ def __init__(self, cfg: RerunVisualizerCfg): def initialize(self, scene_data: dict[str, Any] | None = None) -> None: if self._is_initialized: - logger.warning("[RerunVisualizer] Already initialized. Skipping re-initialization.") + logger.warning("[RerunVisualizer] Already initialized.") return - if scene_data and "scene_data_provider" in scene_data: - self._scene_data_provider = scene_data["scene_data_provider"] - - metadata = {} - if self._scene_data_provider: - self._model = self._scene_data_provider.get_newton_model() - self._state = self._scene_data_provider.get_newton_state() - metadata = self._scene_data_provider.get_metadata() - else: - try: - from isaaclab.sim._impl.newton_manager import NewtonManager - - self._model = NewtonManager._model - self._state = NewtonManager._state_0 - metadata = { - "physics_backend": "newton", - "num_envs": NewtonManager._num_envs if NewtonManager._num_envs is not None else 0, - "gravity_vector": NewtonManager._gravity_vector, - "clone_physics_only": NewtonManager._clone_physics_only, - } - except Exception: - pass - - if self._model is None: - raise RuntimeError( - "Rerun visualizer requires a Newton Model. Ensure a scene data provider is available." - ) + if not scene_data or "scene_data_provider" not in scene_data: + raise RuntimeError("Rerun visualizer requires scene_data_provider.") - if self._state is None: - logger.warning("[RerunVisualizer] No Newton State available. Visualization may not work correctly.") + self._scene_data_provider = scene_data["scene_data_provider"] + self._model = self._scene_data_provider.get_newton_model() + self._state = self._scene_data_provider.get_newton_state() + metadata = self._scene_data_provider.get_metadata() try: if self.cfg.record_to_rrd: @@ -166,25 +131,11 @@ def initialize(self, scene_data: dict[str, Any] | None = None) -> None: raise def step(self, dt: float, state: Any | None = None) -> None: - if not self._is_initialized or self._viewer is None: - logger.warning("[RerunVisualizer] Not initialized. Call initialize() first.") - return - - if self._scene_data_provider: - self._state = self._scene_data_provider.get_newton_state() - else: - try: - from isaaclab.sim._impl.newton_manager import NewtonManager - - self._state = NewtonManager._state_0 - except Exception: - self._state = None - + self._state = self._scene_data_provider.get_newton_state() self._sim_time += dt self._viewer.begin_frame(self._sim_time) - if self._state is not None: - self._viewer.log_state(self._state) + self._viewer.log_state(self._state) self._viewer.end_frame() def close(self) -> None: diff --git a/source/isaaclab/isaaclab/visualizers/visualizer_cfg.py b/source/isaaclab/isaaclab/visualizers/visualizer_cfg.py index 1b3e6777439..988cfdb9baf 100644 --- a/source/isaaclab/isaaclab/visualizers/visualizer_cfg.py +++ b/source/isaaclab/isaaclab/visualizers/visualizer_cfg.py @@ -71,14 +71,6 @@ def create_visualizer(self) -> Visualizer: visualizer_class = get_visualizer_class(self.visualizer_type) if visualizer_class is None: - if self.visualizer_type in ("newton", "rerun"): - raise ImportError( - f"Visualizer '{self.visualizer_type}' requires the Newton Python module and its dependencies. " - "Install the Newton backend (e.g., newton package/isaaclab_newton) and retry." - ) - raise ValueError( - f"Visualizer type '{self.visualizer_type}' is not registered. " - "Valid types: 'newton', 'rerun', 'omniverse'." - ) + raise ValueError(f"Visualizer type '{self.visualizer_type}' is not available.") return visualizer_class(self) From c44efe77205006837c91d6d08cf65a5db2da191b Mon Sep 17 00:00:00 2001 From: Matthew Trepte Date: Wed, 28 Jan 2026 00:16:37 +0000 Subject: [PATCH 37/46] fix ov visualizer, edit docs --- .../visualization.rst | 24 +++++++++---------- .../ov_scene_data_provider.py | 24 +++++-------------- 2 files changed, 18 insertions(+), 30 deletions(-) diff --git a/docs/source/experimental-features/newton-physics-integration/visualization.rst b/docs/source/experimental-features/newton-physics-integration/visualization.rst index 661a98cf9fe..b50d3467f83 100644 --- a/docs/source/experimental-features/newton-physics-integration/visualization.rst +++ b/docs/source/experimental-features/newton-physics-integration/visualization.rst @@ -5,7 +5,7 @@ Visualization Isaac Lab offers several lightweight visualizers for real-time simulation inspection and debugging. Unlike renderers that process sensor data, visualizers are meant for fast, interactive feedback. -You can use any visualizer regardless of your chosen physics engine or rendering backend. +You can launch any number of visualizers at once, and they work with any physics engine or rendering backend. Overview @@ -31,7 +31,7 @@ Isaac Lab supports three visualizer backends, each optimized for different use c - Webviewer, time scrubbing, recording export -*The following visualizers are shown training the Isaac-Velocity-Flat-Anymal-D-v0 environment.* +*The following visualizers are shown training Isaac-Velocity-Flat-Anymal-D-v0 with 4096 concurrent environments.* .. figure:: ../../_static/visualizers/ov_viz.jpg :width: 100% @@ -139,8 +139,8 @@ Omniverse Visualizer window_height=720, # Viewport height in pixels # Camera settings - camera_position=(8.0, 8.0, 3.0), # Initial camera position (x, y, z) - camera_target=(0.0, 0.0, 0.0), # Camera look-at target + camera_position=(8.0, 8.0, 3.0), # Initial camera position (x, y, z) + camera_target=(0.0, 0.0, 0.0), # Camera look-at target # Feature toggles enable_markers=True, # Enable visualization markers @@ -195,8 +195,8 @@ Newton Visualizer window_height=1080, # Window height in pixels # Camera settings - camera_position=(8.0, 8.0, 3.0), # Initial camera position (x, y, z) - camera_target=(0.0, 0.0, 0.0), # Camera look-at target + camera_position=(8.0, 8.0, 3.0), # Initial camera position (x, y, z) + camera_target=(0.0, 0.0, 0.0), # Camera look-at target # Performance tuning update_frequency=1, # Update every N frames (1=every frame) @@ -213,9 +213,9 @@ Newton Visualizer enable_wireframe=False, # Enable wireframe mode # Color customization - sky_upper_color=(0.53, 0.81, 0.92), # Sky upper color (RGB [0,1]) - sky_lower_color=(0.18, 0.20, 0.25), # Sky lower color (RGB [0,1]) - light_color=(1.0, 1.0, 1.0), # Directional light color (RGB [0,1]) + sky_upper_color=(0.53, 0.81, 0.92), # Sky upper color (RGB [0,1]) + sky_lower_color=(0.18, 0.20, 0.25), # Sky lower color (RGB [0,1]) + light_color=(1.0, 1.0, 1.0), # Directional light color (RGB [0,1]) ) @@ -241,8 +241,8 @@ Rerun Visualizer web_port=9090, # Port for local web viewer (launched in browser) # Camera settings - camera_position=(8.0, 8.0, 3.0), # Initial camera position (x, y, z) - camera_target=(0.0, 0.0, 0.0), # Camera look-at target + camera_position=(8.0, 8.0, 3.0), # Initial camera position (x, y, z) + camera_target=(0.0, 0.0, 0.0), # Camera look-at target # History settings keep_historical_data=False, # Keep transforms for time scrubbing @@ -260,7 +260,7 @@ To reduce overhead when visualizing large-scale environments, consider: - Using Newton instead of Omniverse or Rerun - Reducing window sizes -- Higher update frequencies +- Lower update frequencies - Pausing visualizers while they are not being used diff --git a/source/isaaclab/isaaclab/sim/scene_data_providers/ov_scene_data_provider.py b/source/isaaclab/isaaclab/sim/scene_data_providers/ov_scene_data_provider.py index 3a6f1b57ca9..9bdac3b379a 100644 --- a/source/isaaclab/isaaclab/sim/scene_data_providers/ov_scene_data_provider.py +++ b/source/isaaclab/isaaclab/sim/scene_data_providers/ov_scene_data_provider.py @@ -112,28 +112,15 @@ def _refresh_newton_model_if_needed(self) -> None: return def _build_newton_model_from_usd(self) -> None: - # TODO(mtrepte): add support for fabric cloning try: from newton import ModelBuilder - from isaaclab.sim.utils import find_matching_prim_paths - - num_envs = self._get_num_envs() - - # import ipdb; ipdb.set_trace() - env_prim_paths = find_matching_prim_paths("/World/envs/env_.*", stage=self._stage) - print( - "[SceneDataProvider] Stage env prims before add_usd: "+ - f"num_envs_setting={num_envs}, env_prims={len(env_prim_paths)}" - ) builder = ModelBuilder(up_axis=self._up_axis) builder.add_usd(self._stage) - self._newton_model = builder.finalize(device=self._device) - self._metadata["num_envs"] = num_envs - self._newton_model.num_envs = self._metadata.get("num_envs", 0) self._newton_state = self._newton_model.state() self._rigid_body_paths = list(self._newton_model.body_key) + self._xform_views.clear() self._body_key_index_map = {path: i for i, path in enumerate(self._rigid_body_paths)} self._view_body_index_map = {} @@ -343,7 +330,8 @@ def update(self) -> None: for name, getter in pose_sources: positions, orientations = getter() if positions is not None and orientations is not None: - if positions.reshape(-1, 3).shape[0] == expected_count: + count = positions.reshape(-1, 3).shape[0] + if count == expected_count: source_view = name break if positions is None or orientations is None: @@ -370,9 +358,9 @@ def update(self) -> None: return if positions_wp.shape[0] != expected_count: - logger.debug( - "[SceneDataProvider] Body count mismatch for Newton sync " - f"(poses={positions_wp.shape[0]}, state={expected_count}, source={source_view})." + logger.warning( + f"[SceneDataProvider] Body count mismatch for Newton sync: " + f"poses={positions_wp.shape[0]}, state={expected_count}, source={source_view}" ) return From 223c708951cac6e1501965024dceb5a2aff51875 Mon Sep 17 00:00:00 2001 From: Matthew Trepte Date: Thu, 29 Jan 2026 23:07:51 +0000 Subject: [PATCH 38/46] prepping for review --- source/isaaclab/isaaclab/app/app_launcher.py | 5 +-- .../isaaclab/scene/interactive_scene.py | 32 +++++++++++++++++++ .../sim/scene_data_providers/__init__.py | 1 - .../newton_scene_data_provider.py | 11 ++++--- .../ov_scene_data_provider.py | 23 ++----------- .../scene_data_provider.py | 3 +- .../isaaclab/sim/simulation_context.py | 23 ++++++++++--- .../isaaclab/visualizers/newton_visualizer.py | 7 ++-- .../isaaclab/visualizers/rerun_visualizer.py | 6 ++-- .../isaaclab/visualizers/visualizer_cfg.py | 10 +++++- 10 files changed, 79 insertions(+), 42 deletions(-) diff --git a/source/isaaclab/isaaclab/app/app_launcher.py b/source/isaaclab/isaaclab/app/app_launcher.py index a9ac07fbfb8..d066874bd90 100644 --- a/source/isaaclab/isaaclab/app/app_launcher.py +++ b/source/isaaclab/isaaclab/app/app_launcher.py @@ -815,10 +815,7 @@ def _resolve_visualizer_settings(self, launcher_args: dict) -> None: if self._headless: self._headless = False launcher_args["headless"] = False - print( - "[INFO][AppLauncher]: Omniverse visualizer requested. " - "Forcing headless=False for GUI." - ) + print("[INFO][AppLauncher]: Omniverse visualizer requested. Forcing headless=False for GUI.") else: if not self._headless and self._livestream not in {1, 2}: self._headless = True diff --git a/source/isaaclab/isaaclab/scene/interactive_scene.py b/source/isaaclab/isaaclab/scene/interactive_scene.py index 8fb903113c6..f7229c9fce9 100644 --- a/source/isaaclab/isaaclab/scene/interactive_scene.py +++ b/source/isaaclab/isaaclab/scene/interactive_scene.py @@ -181,6 +181,7 @@ def __init__(self, cfg: InteractiveSceneCfg): ), # this won't do anything because we are not replicating physics clone_in_fabric=self.cfg.clone_in_fabric, ) + self._ensure_usd_env_clones(copy_from_source=True) self._default_env_origins = torch.tensor(env_origins, device=self.device, dtype=torch.float32) else: # otherwise, environment origins will be initialized during cloning at the end of environment creation @@ -264,6 +265,7 @@ def clone_environments(self, copy_from_source: bool = False): ), # this automatically filters collisions between environments clone_in_fabric=self.cfg.clone_in_fabric, ) + self._ensure_usd_env_clones(copy_from_source=copy_from_source) # since env_ids is only applicable when replicating physics, we have to fallback to the previous method # to filter collisions if replicate_physics is not enabled @@ -293,6 +295,36 @@ def clone_environments(self, copy_from_source: bool = False): except Exception: pass + def _ensure_usd_env_clones(self, copy_from_source: bool) -> None: + """Ensure USD env prims exist when cloning in fabric.""" + if not self.cfg.clone_in_fabric: + return + if get_isaac_sim_version().major < 5: + return + if not self._should_ensure_usd_env_clones(): + return + + self.cloner.clone( + source_prim_path=self.env_prim_paths[0], + prim_paths=self.env_prim_paths, + replicate_physics=False, + copy_from_source=copy_from_source, + enable_env_ids=False, + clone_in_fabric=False, + ) + + def _should_ensure_usd_env_clones(self) -> bool: + """Check if USD clones are required for current backend/visualizers.""" + sim_cfg = getattr(self.sim, "cfg", None) + if sim_cfg is None: + return True + if sim_cfg.physics_backend != "omni": + return True + + visualizer_types = self.sim.resolve_visualizer_types() + + return bool(visualizer_types) and any(viz_type != "omniverse" for viz_type in visualizer_types) + def filter_collisions(self, global_prim_paths: list[str] | None = None): """Filter environments collisions. diff --git a/source/isaaclab/isaaclab/sim/scene_data_providers/__init__.py b/source/isaaclab/isaaclab/sim/scene_data_providers/__init__.py index 79d7bff100c..243ca11b055 100644 --- a/source/isaaclab/isaaclab/sim/scene_data_providers/__init__.py +++ b/source/isaaclab/isaaclab/sim/scene_data_providers/__init__.py @@ -1,4 +1,3 @@ -#!/usr/bin/env python3 # Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). # All rights reserved. # diff --git a/source/isaaclab/isaaclab/sim/scene_data_providers/newton_scene_data_provider.py b/source/isaaclab/isaaclab/sim/scene_data_providers/newton_scene_data_provider.py index bbeb4794978..43814c48551 100644 --- a/source/isaaclab/isaaclab/sim/scene_data_providers/newton_scene_data_provider.py +++ b/source/isaaclab/isaaclab/sim/scene_data_providers/newton_scene_data_provider.py @@ -1,4 +1,3 @@ -#!/usr/bin/env python3 # Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). # All rights reserved. # @@ -16,7 +15,7 @@ class NewtonSceneDataProvider: """Scene data provider for Newton Warp physics backend. - + Native (cheap): Newton Model/State from NewtonManager Adapted (future): USD stage (would need Newton→USD sync for OV visualizer) """ @@ -50,6 +49,7 @@ def get_newton_model(self) -> Any | None: """NATIVE: Newton Model from NewtonManager.""" try: from isaaclab.sim._impl.newton_manager import NewtonManager + return NewtonManager._model except Exception: return None @@ -58,13 +58,14 @@ def get_newton_state(self) -> Any | None: """NATIVE: Newton State from NewtonManager.""" try: from isaaclab.sim._impl.newton_manager import NewtonManager + return NewtonManager._state_0 except Exception: return None def get_usd_stage(self) -> None: """UNAVAILABLE: Newton backend doesn't provide USD (future: Newton→USD sync).""" - return None + return def get_metadata(self) -> dict[str, Any]: return dict(self._metadata) @@ -76,6 +77,7 @@ def get_transforms(self) -> dict[str, Any] | None: def get_velocities(self) -> dict[str, Any] | None: try: from isaaclab.sim._impl.newton_manager import NewtonManager + if NewtonManager._state_0 is None: return None return {"body_qd": NewtonManager._state_0.body_qd} @@ -85,6 +87,7 @@ def get_velocities(self) -> dict[str, Any] | None: def get_contacts(self) -> dict[str, Any] | None: try: from isaaclab.sim._impl.newton_manager import NewtonManager + if NewtonManager._contacts is None: return None return {"contacts": NewtonManager._contacts} @@ -93,4 +96,4 @@ def get_contacts(self) -> dict[str, Any] | None: def get_mesh_data(self) -> dict[str, Any] | None: """ADAPTED: Extract mesh data from Newton shapes (future work).""" - return None \ No newline at end of file + return None diff --git a/source/isaaclab/isaaclab/sim/scene_data_providers/ov_scene_data_provider.py b/source/isaaclab/isaaclab/sim/scene_data_providers/ov_scene_data_provider.py index 9bdac3b379a..6fc0f80b4cf 100644 --- a/source/isaaclab/isaaclab/sim/scene_data_providers/ov_scene_data_provider.py +++ b/source/isaaclab/isaaclab/sim/scene_data_providers/ov_scene_data_provider.py @@ -1,4 +1,3 @@ -#!/usr/bin/env python3 # Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). # All rights reserved. # @@ -9,7 +8,6 @@ from __future__ import annotations import logging -import os import re from typing import Any @@ -17,13 +15,7 @@ class OVSceneDataProvider: - """Scene data provider for Omni PhysX physics backend. - - Native (cheap): USD stage, PhysX transforms/velocities - Adapted (expensive): Newton Model/State (built from USD, synced each step) - - Performance: Only builds Newton data if Newton/Rerun visualizers are active. - """ + """Scene data provider for Omni PhysX backend.""" def __init__(self, visualizer_cfgs: list[Any] | None, stage, simulation_context) -> None: from isaacsim.core.simulation_manager import SimulationManager @@ -50,7 +42,7 @@ def __init__(self, visualizer_cfgs: list[Any] | None, stage, simulation_context) self._has_rerun_visualizer = True elif viz_type == "omniverse": self._has_ov_visualizer = True - + self._metadata = { "physics_backend": "omni", "num_envs": self._get_num_envs(), @@ -65,7 +57,6 @@ def __init__(self, visualizer_cfgs: list[Any] | None, stage, simulation_context) self._set_body_q_kernel = None self._up_axis = UsdGeom.GetStageUpAxis(self._stage) - # Only build Newton model if Newton/Rerun visualizers need it if self._has_newton_visualizer or self._has_rerun_visualizer: self._build_newton_model_from_usd() self._setup_rigid_body_view() @@ -74,7 +65,6 @@ def __init__(self, visualizer_cfgs: list[Any] | None, stage, simulation_context) logger.info("[OVSceneDataProvider] OV visualizer only - skipping Newton model build") def _get_num_envs(self) -> int: - # TODO(mtrepte): is there a better way to get num_envs? try: import carb @@ -120,7 +110,7 @@ def _build_newton_model_from_usd(self) -> None: self._newton_model = builder.finalize(device=self._device) self._newton_state = self._newton_model.state() self._rigid_body_paths = list(self._newton_model.body_key) - + self._xform_views.clear() self._body_key_index_map = {path: i for i, path in enumerate(self._rigid_body_paths)} self._view_body_index_map = {} @@ -173,7 +163,6 @@ def _setup_articulation_view(self) -> None: self._articulation_view = None def _get_view_world_poses(self, view): - # TODO(mtrepte): this can be revisited & simplifiedafter the function naming gets unified if view is None: return None, None @@ -235,7 +224,6 @@ def _get_view_velocities(self, view): if view is None: return None, None - # Preferred: combined velocities method = getattr(view, "get_velocities", None) if method is not None: try: @@ -247,7 +235,6 @@ def _get_view_velocities(self, view): except Exception: pass - # Fallback: split linear/angular get_linear = getattr(view, "get_linear_velocities", None) get_angular = getattr(view, "get_angular_velocities", None) if get_linear is not None and get_angular is not None: @@ -258,7 +245,6 @@ def _get_view_velocities(self, view): return None, None - def _get_xform_world_poses(self): if not self._rigid_body_paths: return None, None @@ -371,9 +357,6 @@ def update(self) -> None: device=self._device, ) - # Future extensions: - # - Populate velocities into self._newton_state.body_qd - # - Cache mesh/material data for Rerun/renderer integrations except Exception as exc: logger.debug(f"[SceneDataProvider] Failed to sync Omni transforms to Newton state: {exc}") diff --git a/source/isaaclab/isaaclab/sim/scene_data_providers/scene_data_provider.py b/source/isaaclab/isaaclab/sim/scene_data_providers/scene_data_provider.py index a5cebf10e48..14708219c2d 100644 --- a/source/isaaclab/isaaclab/sim/scene_data_providers/scene_data_provider.py +++ b/source/isaaclab/isaaclab/sim/scene_data_providers/scene_data_provider.py @@ -1,4 +1,3 @@ -#!/usr/bin/env python3 # Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). # All rights reserved. # @@ -84,4 +83,4 @@ def get_contacts(self) -> dict[str, Any] | None: def get_mesh_data(self) -> dict[str, Any] | None: if self._provider is None: return None - return self._provider.get_mesh_data() \ No newline at end of file + return self._provider.get_mesh_data() diff --git a/source/isaaclab/isaaclab/sim/simulation_context.py b/source/isaaclab/isaaclab/sim/simulation_context.py index c79aba921e4..eb41a1d9885 100644 --- a/source/isaaclab/isaaclab/sim/simulation_context.py +++ b/source/isaaclab/isaaclab/sim/simulation_context.py @@ -245,6 +245,21 @@ def _create_default_visualizer_configs(self, requested_visualizers: list[str]) - logger.error(f"[SimulationContext] Failed to create default config for visualizer '{viz_type}': {exc}") return default_configs + def resolve_visualizer_types(self) -> list[str]: + """Resolve visualizer types from config or CLI settings.""" + visualizer_cfgs = self.cfg.visualizer_cfgs + if visualizer_cfgs is None: + requested = self.get_setting("/isaaclab/visualizer") + return [v.strip() for v in requested.split(",") if v.strip()] if requested else [] + + if not isinstance(visualizer_cfgs, list): + visualizer_cfgs = [visualizer_cfgs] + return [cfg.visualizer_type for cfg in visualizer_cfgs if getattr(cfg, "visualizer_type", None)] + + def initialize_visualizers(self) -> None: + """Initialize visualizers from SimulationCfg.visualizer_cfgs.""" + self._init_visualizers() + def _init_visualizers(self) -> None: """Initialize visualizers based on config and settings.""" self._visualizers: list[Visualizer] = [] @@ -257,12 +272,10 @@ def _init_visualizers(self) -> None: ] if len(visualizer_cfgs) == 0: - requested_visualizers_str = self.get_setting("/isaaclab/visualizer") - if requested_visualizers_str: - requested_visualizers = [v.strip() for v in requested_visualizers_str.split(",") if v.strip()] - visualizer_cfgs = self._create_default_visualizer_configs(requested_visualizers) - else: + requested_visualizers = self.resolve_visualizer_types() + if not requested_visualizers: return + visualizer_cfgs = self._create_default_visualizer_configs(requested_visualizers) self._scene_data_provider = SceneDataProvider( backend=self.cfg.physics_backend, diff --git a/source/isaaclab/isaaclab/visualizers/newton_visualizer.py b/source/isaaclab/isaaclab/visualizers/newton_visualizer.py index 39c9eddf82d..a2c50b8d640 100644 --- a/source/isaaclab/isaaclab/visualizers/newton_visualizer.py +++ b/source/isaaclab/isaaclab/visualizers/newton_visualizer.py @@ -8,15 +8,18 @@ from __future__ import annotations import contextlib -import numpy as np +import logging from typing import Any +import numpy as np import warp as wp from newton.viewer import ViewerGL from .newton_visualizer_cfg import NewtonVisualizerCfg from .visualizer import Visualizer +logger = logging.getLogger(__name__) + class NewtonViewerGL(ViewerGL): """Wrapper around Newton's ViewerGL with training/rendering pause controls.""" @@ -264,7 +267,7 @@ def step(self, dt: float, state: Any | None = None) -> None: self._step_counter += 1 self._state = self._scene_data_provider.get_newton_state() - + contacts = None if self._viewer.show_contacts: contacts_data = self._scene_data_provider.get_contacts() diff --git a/source/isaaclab/isaaclab/visualizers/rerun_visualizer.py b/source/isaaclab/isaaclab/visualizers/rerun_visualizer.py index 00d2623001e..d73e313cfdd 100644 --- a/source/isaaclab/isaaclab/visualizers/rerun_visualizer.py +++ b/source/isaaclab/isaaclab/visualizers/rerun_visualizer.py @@ -10,13 +10,13 @@ import logging from typing import Any -from .rerun_visualizer_cfg import RerunVisualizerCfg -from .visualizer import Visualizer - import rerun as rr import rerun.blueprint as rrb from newton.viewer import ViewerRerun +from .rerun_visualizer_cfg import RerunVisualizerCfg +from .visualizer import Visualizer + logger = logging.getLogger(__name__) diff --git a/source/isaaclab/isaaclab/visualizers/visualizer_cfg.py b/source/isaaclab/isaaclab/visualizers/visualizer_cfg.py index 988cfdb9baf..1b3e6777439 100644 --- a/source/isaaclab/isaaclab/visualizers/visualizer_cfg.py +++ b/source/isaaclab/isaaclab/visualizers/visualizer_cfg.py @@ -71,6 +71,14 @@ def create_visualizer(self) -> Visualizer: visualizer_class = get_visualizer_class(self.visualizer_type) if visualizer_class is None: - raise ValueError(f"Visualizer type '{self.visualizer_type}' is not available.") + if self.visualizer_type in ("newton", "rerun"): + raise ImportError( + f"Visualizer '{self.visualizer_type}' requires the Newton Python module and its dependencies. " + "Install the Newton backend (e.g., newton package/isaaclab_newton) and retry." + ) + raise ValueError( + f"Visualizer type '{self.visualizer_type}' is not registered. " + "Valid types: 'newton', 'rerun', 'omniverse'." + ) return visualizer_class(self) From f4c5cc7e6b5d6852c59ba1686cfa9b26f57c4630 Mon Sep 17 00:00:00 2001 From: Matthew Trepte Date: Fri, 30 Jan 2026 19:23:50 +0000 Subject: [PATCH 39/46] sanatize ov camera path --- source/isaaclab/isaaclab/visualizers/ov_visualizer.py | 4 +++- .../benchmarking/configs_custom_reward_thresholds.yaml | 9 +++++++++ 2 files changed, 12 insertions(+), 1 deletion(-) create mode 100644 source/isaaclab_tasks/test/benchmarking/configs_custom_reward_thresholds.yaml diff --git a/source/isaaclab/isaaclab/visualizers/ov_visualizer.py b/source/isaaclab/isaaclab/visualizers/ov_visualizer.py index 33596629561..d3e2c8ea822 100644 --- a/source/isaaclab/isaaclab/visualizers/ov_visualizer.py +++ b/source/isaaclab/isaaclab/visualizers/ov_visualizer.py @@ -178,7 +178,9 @@ async def _dock_viewport_async(self, viewport_name: str, dock_position) -> None: viewport_window.focus() def _create_and_assign_camera(self, usd_stage) -> None: - camera_path = f"/World/Cameras/{self.cfg.viewport_name}_Camera" + # Create camera prim path based on viewport name (sanitize to enure valid USD path) 1 + camera_path = f"/World/Cameras/{self.cfg.viewport_name}_Camera".replace(" ", "_") + camera_prim = usd_stage.GetPrimAtPath(camera_path) if not camera_prim.IsValid(): UsdGeom.Camera.Define(usd_stage, camera_path) diff --git a/source/isaaclab_tasks/test/benchmarking/configs_custom_reward_thresholds.yaml b/source/isaaclab_tasks/test/benchmarking/configs_custom_reward_thresholds.yaml new file mode 100644 index 00000000000..cb899cd591b --- /dev/null +++ b/source/isaaclab_tasks/test/benchmarking/configs_custom_reward_thresholds.yaml @@ -0,0 +1,9 @@ +custom_rewards: + rl_games:Isaac-Dexsuite-Kuka-Allegro-Lift-v0: + max_iterations: 2000 + upper_thresholds: + duration: 999999 + sb3:Isaac-Lift-Cube-Franka-v0: + max_iterations: 200 + upper_thresholds: + duration: 999999 From b5c03cdb2f71427a73287a7349445af498da30fe Mon Sep 17 00:00:00 2001 From: Matthew Trepte Date: Tue, 3 Feb 2026 01:11:24 +0000 Subject: [PATCH 40/46] refactor scene data provider, unify apis --- .../ov_scene_data_provider.py | 283 ++++++++++-------- 1 file changed, 166 insertions(+), 117 deletions(-) diff --git a/source/isaaclab/isaaclab/sim/scene_data_providers/ov_scene_data_provider.py b/source/isaaclab/isaaclab/sim/scene_data_providers/ov_scene_data_provider.py index 6fc0f80b4cf..100ff7f0b10 100644 --- a/source/isaaclab/isaaclab/sim/scene_data_providers/ov_scene_data_provider.py +++ b/source/isaaclab/isaaclab/sim/scene_data_providers/ov_scene_data_provider.py @@ -30,6 +30,7 @@ def __init__(self, visualizer_cfgs: list[Any] | None, stage, simulation_context) self._body_key_index_map: dict[str, int] = {} self._view_body_index_map: dict[str, list[int]] = {} + # Determine which visualizers need Newton state sync self._has_newton_visualizer = False self._has_rerun_visualizer = False self._has_ov_visualizer = False @@ -43,6 +44,9 @@ def __init__(self, visualizer_cfgs: list[Any] | None, stage, simulation_context) elif viz_type == "omniverse": self._has_ov_visualizer = True + # Explicit mode flag for Newton synchronization + self._needs_newton_sync = self._has_newton_visualizer or self._has_rerun_visualizer + self._metadata = { "physics_backend": "omni", "num_envs": self._get_num_envs(), @@ -54,14 +58,16 @@ def __init__(self, visualizer_cfgs: list[Any] | None, stage, simulation_context) self._newton_model = None self._newton_state = None self._rigid_body_paths: list[str] = [] + self._articulation_paths: list[str] = [] self._set_body_q_kernel = None self._up_axis = UsdGeom.GetStageUpAxis(self._stage) - if self._has_newton_visualizer or self._has_rerun_visualizer: + # Initialize Newton pipeline only if needed for visualization + if self._needs_newton_sync: self._build_newton_model_from_usd() self._setup_rigid_body_view() self._setup_articulation_view() - elif self._has_ov_visualizer: + else: logger.info("[OVSceneDataProvider] OV visualizer only - skipping Newton model build") def _get_num_envs(self) -> int: @@ -102,6 +108,7 @@ def _refresh_newton_model_if_needed(self) -> None: return def _build_newton_model_from_usd(self) -> None: + """Build Newton model from USD and extract scene structure.""" try: from newton import ModelBuilder @@ -109,7 +116,10 @@ def _build_newton_model_from_usd(self) -> None: builder.add_usd(self._stage) self._newton_model = builder.finalize(device=self._device) self._newton_state = self._newton_model.state() + + # Extract scene structure from Newton model (single source of truth) self._rigid_body_paths = list(self._newton_model.body_key) + self._articulation_paths = list(self._newton_model.articulation_key) self._xform_views.clear() self._body_key_index_map = {path: i for i, path in enumerate(self._rigid_body_paths)} @@ -125,12 +135,18 @@ def _build_newton_model_from_usd(self) -> None: self._newton_model = None self._newton_state = None self._rigid_body_paths = [] + self._articulation_paths = [] def _setup_rigid_body_view(self) -> None: + """Create PhysX RigidBodyView from Newton's body paths. + + Uses body paths extracted from Newton model to create PhysX tensor API view + for reading rigid body transforms. + """ if not self._rigid_body_paths: return try: - paths_to_use = self._wildcard_env_paths(list(self._rigid_body_paths)) + paths_to_use = self._wildcard_env_paths(self._rigid_body_paths) self._rigid_body_view = self._physics_sim_view.create_rigid_body_view(paths_to_use) self._cache_view_index_map(self._rigid_body_view, "rigid_body_view") except Exception as exc: @@ -138,21 +154,11 @@ def _setup_rigid_body_view(self) -> None: self._rigid_body_view = None def _setup_articulation_view(self) -> None: + """Create PhysX ArticulationView from Newton's articulation paths.""" + if not self._articulation_paths: + return try: - from pxr import UsdPhysics - - from isaaclab.sim.utils import get_all_matching_child_prims - - root_prims = get_all_matching_child_prims( - "/World", - predicate=lambda prim: prim.HasAPI(UsdPhysics.ArticulationRootAPI), - stage=self._stage, - traverse_instance_prims=True, - ) - if not root_prims: - return - - paths_to_use = self._wildcard_env_paths([prim.GetPath().pathString for prim in root_prims]) + paths_to_use = self._wildcard_env_paths(self._articulation_paths) exprs = [path.replace(".*", "*") for path in paths_to_use] self._articulation_view = self._physics_sim_view.create_articulation_view( exprs if len(exprs) > 1 else exprs[0] @@ -163,15 +169,15 @@ def _setup_articulation_view(self) -> None: self._articulation_view = None def _get_view_world_poses(self, view): + """Read world poses from PhysX tensor API view (ArticulationView or RigidBodyView). + + Tries multiple method names for compatibility across PhysX API versions. + Returns (positions, orientations) tuple or (None, None) if unavailable. + """ if view is None: return None, None - method_names = ( - "get_world_poses", - "get_world_transforms", - "get_transforms", - "get_poses", - ) + method_names = ("get_world_poses", "get_world_transforms", "get_transforms", "get_poses") for name in method_names: method = getattr(view, name, None) @@ -182,9 +188,11 @@ def _get_view_world_poses(self, view): except Exception: continue + # Handle tuple return: (positions, orientations) if isinstance(result, tuple) and len(result) == 2: return result + # Handle packed array: [..., 7] -> split into pos and quat try: if hasattr(result, "shape") and result.shape[-1] == 7: positions = result[..., :3] @@ -196,25 +204,29 @@ def _get_view_world_poses(self, view): return None, None def _cache_view_index_map(self, view, key: str) -> None: + """Map PhysX view indices to Newton body_key ordering.""" prim_paths = getattr(view, "prim_paths", None) if not prim_paths or not self._rigid_body_paths: return def split_env(path: str) -> tuple[int | None, str]: + """Extract environment ID and relative path from prim path.""" match = re.search(r"/World/envs/env_(\d+)(/.*)", path) return (int(match.group(1)), match.group(2)) if match else (None, path) + # Build map: (env_id, relative_path) -> view_index view_map: dict[tuple[int | None, str], int] = {} for view_idx, path in enumerate(prim_paths): env_id, rel = split_env(path) view_map[(env_id, rel)] = view_idx + # Build reordering: newton_body_index -> view_index order: list[int | None] = [None] * len(self._rigid_body_paths) for body_idx, path in enumerate(self._rigid_body_paths): env_id, rel = split_env(path) view_idx = view_map.get((env_id, rel)) if view_idx is None: - view_idx = view_map.get((None, rel)) + view_idx = view_map.get((None, rel)) # Try without env_id order[body_idx] = view_idx if all(idx is not None for idx in order): @@ -245,30 +257,116 @@ def _get_view_velocities(self, view): return None, None - def _get_xform_world_poses(self): - if not self._rigid_body_paths: - return None, None - try: - import torch - - from isaaclab.sim.views import XformPrimView - - positions = [] - orientations = [] - for path in self._rigid_body_paths: - view = self._xform_views.get(path) - if view is None: - view = XformPrimView(path, device=self._device, stage=self._stage, validate_xform_ops=False) - self._xform_views[path] = view - pos, quat = view.get_world_poses() - positions.append(pos) - orientations.append(quat) - return (torch.cat(positions, dim=0), torch.cat(orientations, dim=0)) if positions else (None, None) - except Exception as exc: - logger.debug(f"[SceneDataProvider] Failed to read XformPrimView poses: {exc}") - return None, None + def _apply_view_poses(self, view: Any, view_key: str, positions: Any, orientations: Any, covered: Any) -> int: + """Read poses from a PhysX view and write uncovered bodies to output tensors.""" + import torch + + if view is None: + return 0 + + pos, quat = self._get_view_world_poses(view) + if pos is None or quat is None: + return 0 + + order = self._view_body_index_map.get(view_key) + if not order: + return 0 + + pos = pos.to(device=self._device, dtype=torch.float32) + quat = quat.to(device=self._device, dtype=torch.float32) + + count = 0 + for newton_idx, view_idx in enumerate(order): + if view_idx is not None and not covered[newton_idx]: + positions[newton_idx] = pos[view_idx] + orientations[newton_idx] = quat[view_idx] + covered[newton_idx] = True + count += 1 + + return count + + def _apply_xform_poses(self, positions: Any, orientations: Any, covered: Any, xform_mask: Any) -> int: + """Use XformPrimView fallback for remaining uncovered bodies.""" + import torch + + from isaaclab.sim.views import XformPrimView + + uncovered = torch.where(~covered)[0].cpu().tolist() + if not uncovered: + return 0 + + count = 0 + for idx in uncovered: + path = self._rigid_body_paths[idx] + try: + if path not in self._xform_views: + self._xform_views[path] = XformPrimView( + path, device=self._device, stage=self._stage, validate_xform_ops=False + ) + + pos, quat = self._xform_views[path].get_world_poses() + if pos is not None and quat is not None: + positions[idx] = pos.to(device=self._device, dtype=torch.float32).squeeze() + orientations[idx] = quat.to(device=self._device, dtype=torch.float32).squeeze() + covered[idx] = True + xform_mask[idx] = True + count += 1 + except Exception: + continue + + return count + + def _convert_xform_quats(self, orientations: Any, xform_mask: Any) -> Any: + """Convert XformPrimView quaternions from wxyz to xyzw where needed.""" + if not xform_mask.any(): + return orientations + + import torch + + from isaaclab.utils.math import convert_quat + + orientations_xyzw = orientations.clone() + xform_indices = torch.where(xform_mask)[0] + if len(xform_indices) > 0: + orientations_xyzw[xform_indices] = convert_quat(orientations[xform_indices], to="xyzw") + return orientations_xyzw + + def _read_poses_from_best_source(self) -> tuple[Any, Any, str, Any] | None: + """Merge pose data from ArticulationView, RigidBodyView, and XformPrimView.""" + if self._newton_state is None or not self._rigid_body_paths: + return None + + import torch + + num_bodies = len(self._rigid_body_paths) + if num_bodies != self._newton_state.body_q.shape[0]: + logger.warning(f"Body count mismatch: body_key={num_bodies}, state={self._newton_state.body_q.shape[0]}") + return None + + positions = torch.zeros((num_bodies, 3), dtype=torch.float32, device=self._device) + orientations = torch.zeros((num_bodies, 4), dtype=torch.float32, device=self._device) + covered = torch.zeros(num_bodies, dtype=torch.bool, device=self._device) + xform_mask = torch.zeros(num_bodies, dtype=torch.bool, device=self._device) + + artic = self._apply_view_poses(self._articulation_view, "articulation_view", positions, orientations, covered) + rigid = self._apply_view_poses(self._rigid_body_view, "rigid_body_view", positions, orientations, covered) + xform = self._apply_xform_poses(positions, orientations, covered, xform_mask) + + if not covered.all(): + logger.warning(f"Failed to read {(~covered).sum().item()}/{num_bodies} body poses") + return None + + active = sum([artic > 0, rigid > 0, xform > 0]) + source = ( + "merged" + if active > 1 + else ("articulation_view" if artic else "rigid_body_view" if rigid else "xform_view" if xform else "none") + ) + + return positions, orientations, source, xform_mask def _get_set_body_q_kernel(self): + """Get or create the Warp kernel for writing transforms to Newton state.""" if self._set_body_q_kernel is not None: return self._set_body_q_kernel try: @@ -290,64 +388,27 @@ def _set_body_q( return None def update(self) -> None: - """Sync PhysX transforms to Newton state if Newton/Rerun visualizers are active.""" - if not (self._has_newton_visualizer or self._has_rerun_visualizer): - return # OV visualizer only - USD auto-synced by omni.physics - self._refresh_newton_model_if_needed() - if self._newton_state is None: - return - if self._rigid_body_view is None and self._articulation_view is None and not self._rigid_body_paths: + """Sync PhysX transforms to Newton state for visualization.""" + if not self._needs_newton_sync or self._newton_state is None: return + self._refresh_newton_model_if_needed() + try: - import torch import warp as wp - from isaaclab.utils.math import convert_quat - - expected_count = self._newton_state.body_q.shape[0] - pose_sources = ( - ("articulation_view", lambda: self._get_view_world_poses(self._articulation_view)), - ("rigid_body_view", lambda: self._get_view_world_poses(self._rigid_body_view)), - ("xform_view", self._get_xform_world_poses), - ) - positions = orientations = None - source_view = "none" - for name, getter in pose_sources: - positions, orientations = getter() - if positions is not None and orientations is not None: - count = positions.reshape(-1, 3).shape[0] - if count == expected_count: - source_view = name - break - if positions is None or orientations is None: + result = self._read_poses_from_best_source() + if result is None: return - order = self._view_body_index_map.get(source_view) - if order: - positions = positions[order] - orientations = orientations[order] - - positions = positions.reshape(-1, 3).to(dtype=torch.float32, device=self._device) - orientations = orientations.reshape(-1, 4).to(dtype=torch.float32, device=self._device) - # NOTE: PhysX tensor views return quats in xyzw, while XformPrimView returns wxyz. - # Convert only when needed to avoid scrambling orientations. - if source_view == "xform_view": - orientations_xyzw = convert_quat(orientations, to="xyzw") - else: - orientations_xyzw = orientations - - positions_wp = wp.from_torch(positions, dtype=wp.vec3) + + positions, orientations, _, xform_mask = result + orientations_xyzw = self._convert_xform_quats(orientations.reshape(-1, 4), xform_mask) + + positions_wp = wp.from_torch(positions.reshape(-1, 3), dtype=wp.vec3) orientations_wp = wp.from_torch(orientations_xyzw, dtype=wp.quatf) set_body_q = self._get_set_body_q_kernel() - if set_body_q is None: - return - - if positions_wp.shape[0] != expected_count: - logger.warning( - f"[SceneDataProvider] Body count mismatch for Newton sync: " - f"poses={positions_wp.shape[0]}, state={expected_count}, source={source_view}" - ) + if set_body_q is None or positions_wp.shape[0] != self._newton_state.body_q.shape[0]: return wp.launch( @@ -358,44 +419,32 @@ def update(self) -> None: ) except Exception as exc: - logger.debug(f"[SceneDataProvider] Failed to sync Omni transforms to Newton state: {exc}") + logger.debug(f"Failed to sync transforms to Newton: {exc}") def get_newton_model(self) -> Any | None: - """ADAPTED: Newton Model built from USD (only if Newton/Rerun visualizers active).""" - if not (self._has_newton_visualizer or self._has_rerun_visualizer): - return None - return self._newton_model + return self._newton_model if self._needs_newton_sync else None def get_newton_state(self) -> Any | None: - """ADAPTED: Newton State synced from PhysX (only if Newton/Rerun visualizers active).""" - if not (self._has_newton_visualizer or self._has_rerun_visualizer): - return None - return self._newton_state + return self._newton_state if self._needs_newton_sync else None def get_usd_stage(self) -> Any: - """NATIVE: USD stage.""" return self._stage def get_mesh_data(self) -> dict[str, Any] | None: - """NATIVE: Extract mesh data from USD stage (future work).""" return None def get_metadata(self) -> dict[str, Any]: return dict(self._metadata) def get_transforms(self) -> dict[str, Any] | None: - if self._rigid_body_view is None and self._articulation_view is None: - return None try: - for getter in ( - lambda: self._get_view_world_poses(self._articulation_view), - lambda: self._get_view_world_poses(self._rigid_body_view), - self._get_xform_world_poses, - ): - positions, orientations = getter() - if positions is not None and orientations is not None: - return {"positions": positions, "orientations": orientations} - return None + result = self._read_poses_from_best_source() + if result is None: + return None + + positions, orientations, _, xform_mask = result + orientations_xyzw = self._convert_xform_quats(orientations, xform_mask) + return {"positions": positions, "orientations": orientations_xyzw} except Exception: return None From 181a21cc4b30834ff7f4fba7c1d0dae3649524af Mon Sep 17 00:00:00 2001 From: Matthew Trepte Date: Fri, 6 Feb 2026 01:35:02 +0000 Subject: [PATCH 41/46] prepr --- scripts/warp_renderer/example.py | 147 ++++++++++ .../isaaclab/isaaclab/renderers/__init__.py | 1 + .../renderers/newton_warp_renderer.py | 140 +++++++++ .../renderers/newton_warp_renderer_direct.py | 269 ++++++++++++++++++ .../newton_scene_data_provider.py | 12 +- .../ov_scene_data_provider.py | 250 ++++++++++++---- .../scene_data_provider.py | 14 +- source/isaaclab/setup.py | 2 +- .../configs_custom_reward_thresholds.yaml | 5 + 9 files changed, 779 insertions(+), 61 deletions(-) create mode 100644 scripts/warp_renderer/example.py create mode 100644 source/isaaclab/isaaclab/renderers/__init__.py create mode 100644 source/isaaclab/isaaclab/renderers/newton_warp_renderer.py create mode 100644 source/isaaclab/isaaclab/renderers/newton_warp_renderer_direct.py diff --git a/scripts/warp_renderer/example.py b/scripts/warp_renderer/example.py new file mode 100644 index 00000000000..fe00a37cc3e --- /dev/null +++ b/scripts/warp_renderer/example.py @@ -0,0 +1,147 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +import argparse +import contextlib +import time + +from isaaclab.app import AppLauncher + + +@contextlib.contextmanager +def measure_time(title: str, iterations: int = 1): + start_time = time.perf_counter_ns() + yield + end_time = time.perf_counter_ns() + print(f"[BENCHMARK] {title}: {(end_time - start_time) / iterations / 1e6:.2f} ms") + + +@contextlib.contextmanager +def launch_app(args): + with measure_time("App start time"): + app_launcher = AppLauncher(args) + yield app_launcher.app + if app_launcher.app: + app_launcher.app.close() + + +parser = argparse.ArgumentParser(description="Benchmark Warp Raytrace") +parser.add_argument("--num_envs", type=int, default=32, help="Number of robots to simulate") +parser.add_argument("--save_images", action="store_true", help="Save Sensor Images") +parser.add_argument("--steps", type=int, default=2000, help="Number of steps to simulate") + +AppLauncher.add_app_launcher_args(parser) +args, _ = parser.parse_known_args() + +app_launcher = AppLauncher(args) + +with measure_time("Imports time"): + import torch + + import isaaclab.sim as isaaclab_sim + from isaaclab.assets import Articulation, ArticulationCfg, AssetBaseCfg + from isaaclab.renderers import NewtonWarpRenderer as NewtonWarpRenderer + from isaaclab.scene import InteractiveScene, InteractiveSceneCfg + from isaaclab.sensors import TiledCamera, TiledCameraCfg + from isaaclab.utils import configclass + + from isaaclab_assets import ANYMAL_D_CFG + + +@configclass +class SceneCfg(InteractiveSceneCfg): + ground = AssetBaseCfg(prim_path="/World/defaultGroundPlane", spawn=isaaclab_sim.GroundPlaneCfg()) + dome_light = AssetBaseCfg( + prim_path="/World/Light", + spawn=isaaclab_sim.DomeLightCfg(intensity=3000.0, color=(0.75, 0.75, 0.75)), + ) + robot: ArticulationCfg = ANYMAL_D_CFG + robot.prim_path = "{ENV_REGEX_NS}/Robot" + + +def run_simulator( + sim: isaaclab_sim.SimulationContext, + scene: InteractiveScene, + num_steps: int, + renderer: NewtonWarpRenderer, + save_images: bool, +): + robot: Articulation = scene["robot"] + for step in range(num_steps): + if step % 500 == 0: + # reset the scene entities root state we offset the root state by the origin since the states are + # written in simulation world frame if this is not done, then the robots will be spawned at + # the (0, 0, 0) of the simulation world + + root_state = robot.data.default_root_state.clone() + root_state[:, :3] += scene.env_origins + robot.write_root_pose_to_sim(root_state[:, :7]) + robot.write_root_velocity_to_sim(root_state[:, 7:]) + # set joint positions with some noise + joint_pos, joint_vel = robot.data.default_joint_pos.clone(), robot.data.default_joint_vel.clone() + joint_pos += torch.rand_like(joint_pos) * 0.1 + robot.write_joint_state_to_sim(joint_pos, joint_vel) + # clear internal buffers + scene.reset() + + # Apply random action + efforts = torch.randn_like(robot.data.joint_pos) * 5.0 + robot.set_joint_effort_target(efforts) + + scene.write_data_to_sim() + sim.step() + scene.update(sim.get_physics_dt()) + + renderer.update() + renderer.render_all() + if save_images: + renderer.camera_manager.save_images(f"__warp_renderer/%s_rgb.{step:04d}.png") + + +def main(): + with measure_time("Simulation Context creation time"): + sim_cfg = isaaclab_sim.SimulationCfg(device="cuda:0") + sim = isaaclab_sim.SimulationContext(sim_cfg) + + sim.set_camera_view((2.5, 0.0, 4.0), (0.0, 0.0, 2.0)) + + with measure_time("Scene creation time"): + scene_cfg = SceneCfg(num_envs=args.num_envs, env_spacing=2.0) + scene = InteractiveScene(scene_cfg) + + tiled_camera_cfg: TiledCameraCfg = TiledCameraCfg( + prim_path="/World/envs/env_.*/Camera", + offset=TiledCameraCfg.OffsetCfg( + pos=(-3.0, 0.0, 1.0), + rot=(0.0, 0.0, 0.0, 1.0), + convention="world", + ), + data_types=["rgb"], + spawn=isaaclab_sim.PinholeCameraCfg( + focal_length=24.0, + focus_distance=400.0, + horizontal_aperture=20.955, + clipping_range=(0.1, 20.0), + ), + width=400, + height=400, + ) + scene.sensors["tiled_camera"] = TiledCamera(tiled_camera_cfg) + + renderer = NewtonWarpRenderer(scene) + + # stage = isaaclab_sim.get_current_stage() + # stage.Export("/home/dhasenbring/development/isaac/IsaacLab/stage.usda") + + with measure_time("Sim start time"): + sim.reset() + + with measure_time("Average sim step time", iterations=args.steps): + run_simulator(sim, scene, args.steps, renderer, args.save_images) + + +if __name__ == "__main__": + main() + app_launcher.app.close() diff --git a/source/isaaclab/isaaclab/renderers/__init__.py b/source/isaaclab/isaaclab/renderers/__init__.py new file mode 100644 index 00000000000..55a51a7e2b5 --- /dev/null +++ b/source/isaaclab/isaaclab/renderers/__init__.py @@ -0,0 +1 @@ +from .newton_warp_renderer import NewtonWarpRenderer diff --git a/source/isaaclab/isaaclab/renderers/newton_warp_renderer.py b/source/isaaclab/isaaclab/renderers/newton_warp_renderer.py new file mode 100644 index 00000000000..45ca31655a1 --- /dev/null +++ b/source/isaaclab/isaaclab/renderers/newton_warp_renderer.py @@ -0,0 +1,140 @@ +from isaaclab.utils.math import convert_camera_frame_orientation_convention +from isaaclab.scene import InteractiveScene +from isaaclab.sensors import TiledCamera +import isaaclab.sim as isaaclab_sim + +from dataclasses import dataclass, field +from pxr import Usd + +import newton +import warp as wp +import os + + +class CameraManager: + @dataclass + class CameraData: + camera_rays: wp.array(dtype=wp.vec3f, ndim=4) = None + color_image: wp.array(dtype=wp.uint32, ndim=4) = None + prims: list[Usd.Prim] = field(default_factory=lambda: []) + width: int = 100 + height: int = 100 + + def __init__(self, scene: InteractiveScene): + self.render_context: newton.sensors.SensorTiledCamera.RenderContext | None = None + self.scene = scene + self.num_cameras = 1 + self.camera_data: dict[str, CameraManager.CameraData] = {} + + for name, sensor in self.scene.sensors.items(): + camera_data = CameraManager.CameraData() + camera_data.prims = isaaclab_sim.find_matching_prims(sensor.cfg.prim_path) + if isinstance(sensor, TiledCamera): + camera_data.width = sensor.cfg.width + camera_data.height = sensor.cfg.height + self.camera_data[name] = camera_data + + def create_outputs(self, render_context: newton.sensors.SensorTiledCamera.RenderContext): + self.render_context = render_context + for name in self.scene.sensors: + camera_fovs = wp.array([20.0] * self.num_cameras, dtype=wp.float32) + self.camera_data[name].camera_rays = render_context.utils.compute_pinhole_camera_rays(self.camera_data[name].width, self.camera_data[name].height, camera_fovs) + self.camera_data[name].color_image = render_context.create_color_image_output(self.camera_data[name].width, self.camera_data[name].height, self.num_cameras) + + def get_camera_transforms(self, camera_data: CameraData) -> wp.array(dtype=wp.transformf): + camera_transforms = [] + for prim in camera_data.prims: + camera_transforms.append(self.__resolve_camera_transform(prim)) + return wp.array([camera_transforms], dtype=wp.transformf) + + def save_images(self, filename: str): + if self.render_context is None: + return + + for name, camera_data in self.camera_data.items(): + color_data = self.render_context.utils.flatten_color_image_to_rgba(camera_data.color_image) + + from PIL import Image + os.makedirs(os.path.dirname(filename), exist_ok=True) + Image.fromarray(color_data.numpy()).save(filename % name) + + def __resolve_camera_transform(self, prim: Usd.Prim) -> wp.transformf: + position, orientation = isaaclab_sim.resolve_prim_pose(prim) + return wp.transformf(position, wp.quatf(orientation[1], -orientation[2], -orientation[3], orientation[0])) + # position, orientation = isaaclab_sim.resolve_prim_pose(prim) + # t = torch.tensor(orientation, dtype=torch.float32, device="cpu").unsqueeze(0) + # t = convert_camera_frame_orientation_convention(t) + # orientation = t.squeeze(0).cpu().numpy() + # return wp.transformf(position, wp.quatf(orientation)) + + +class NewtonWarpRenderer: + def __init__(self, scene: InteractiveScene): + self.scene = scene + + builder = newton.ModelBuilder() + builder.add_usd(isaaclab_sim.get_current_stage(), ignore_paths=[r"/World/envs/.*"]) + for world_id in range(scene.num_envs): + builder.begin_world() + for name, articulation in self.scene.articulations.items(): + path = articulation.cfg.prim_path.replace(".*", str(world_id)) + builder.add_usd(isaaclab_sim.get_current_stage(), root_path=path) + builder.end_world() + + self.newton_model = builder.finalize() + self.newton_state = self.newton_model.state() + + self.physx_to_newton_body_mapping: dict[str, wp.array(dtype=wp.int32, ndim=2)] = {} + + self.camera_manager = CameraManager(scene) + self.newton_sensor = newton.sensors.SensorTiledCamera(self.newton_model) + self.camera_manager.create_outputs(self.newton_sensor.render_context) + + def update(self): + self.__update_mapping() + for name, articulation in self.scene.articulations.items(): + if mapping := self.physx_to_newton_body_mapping.get(name): + physx_pos = wp.from_torch(articulation.data.body_pos_w) + physx_quat = wp.from_torch(articulation.data.body_quat_w) + wp.launch(NewtonWarpRenderer.__update_transforms, mapping.shape, [mapping, self.newton_model.body_world, physx_pos, physx_quat, self.newton_state.body_q]) + + def render(self, sensor_name: str): + if camera_data := self.camera_manager.camera_data.get(sensor_name): + self.__render(camera_data) + + def render_all(self): + for name, camera_data in self.camera_manager.camera_data.items(): + self.__render(camera_data) + + def __render(self, camera_data: CameraManager.CameraData): + self.newton_sensor.render(self.newton_state, self.camera_manager.get_camera_transforms(camera_data), camera_data.camera_rays, camera_data.color_image) + + def __update_mapping(self): + if self.physx_to_newton_body_mapping: + return + + self.physx_to_newton_body_mapping.clear() + for name, articulation in self.scene.articulations.items(): + articulation_mapping = [] + for prim in isaaclab_sim.find_matching_prims(articulation.cfg.prim_path): + body_indices = [] + for body_name in articulation.body_names: + prim_path = prim.GetPath().AppendChild(body_name).pathString + body_indices.append(self.newton_model.body_key.index(prim_path)) + articulation_mapping.append(body_indices) + self.physx_to_newton_body_mapping[name] = wp.array(articulation_mapping, dtype=wp.int32) + + @wp.kernel(enable_backward=False) + def __update_transforms(mapping: wp.array(dtype=wp.int32, ndim=2), newton_body_world: wp.array(dtype=wp.int32), physx_pos: wp.array(dtype=wp.float32, ndim=3), physx_quat: wp.array(dtype=wp.float32, ndim=3), out_transform: wp.array(dtype=wp.transformf)): + physx_world_id, physx_body_id = wp.tid() + + newton_body_index = mapping[physx_world_id, physx_body_id] + newton_world_id = newton_body_world[newton_body_index] + + pos_raw = physx_pos[newton_world_id, physx_body_id] + pos = wp.vec3f(pos_raw[0], pos_raw[1], pos_raw[2]) + + quat_raw = physx_quat[newton_world_id, physx_body_id] + quat = wp.quatf(quat_raw[1], quat_raw[2], quat_raw[3], quat_raw[0]) + + out_transform[newton_body_index] = wp.transformf(pos, quat) diff --git a/source/isaaclab/isaaclab/renderers/newton_warp_renderer_direct.py b/source/isaaclab/isaaclab/renderers/newton_warp_renderer_direct.py new file mode 100644 index 00000000000..1aebac7dd27 --- /dev/null +++ b/source/isaaclab/isaaclab/renderers/newton_warp_renderer_direct.py @@ -0,0 +1,269 @@ +from isaaclab.scene import InteractiveScene +import isaaclab.sim as isaaclab_sim + +from dataclasses import dataclass, field +from pxr import Usd, UsdGeom + +from newton.sensors import SensorTiledCamera +import numpy as np +import warp as wp +import usdrt +import re + +from isaaclab.renderers.newton_warp_renderer import CameraManager + +@wp.kernel(enable_backward=False) +def compute_triangle_count(num_face_counts: wp.int32, face_counts: wp.array(dtype=wp.int32), out_face_offsets: wp.array(dtype=wp.int32)): + offset = wp.int32(0) + for i in range(num_face_counts): + out_face_offsets[i] = offset + offset += face_counts[i] + out_face_offsets[num_face_counts] = offset - num_face_counts * 2 + + +@wp.kernel(enable_backward=False) +def triangulate_faces(num_face_counts: wp.int32, face_counts: wp.array(dtype=wp.int32), face_indices: wp.array(dtype=wp.int32), face_offsets: wp.array(dtype=wp.int32), out_triangles: wp.array(dtype=wp.int32)): + offset = face_offsets[wp.tid()] + num_triangles = face_counts[wp.tid()] - 2 + tri = wp.atomic_add(face_offsets, num_face_counts + 1, num_triangles * 3) + + for i in range(num_triangles): + out_triangles[tri + i * 3 + 0] = face_indices[offset] + out_triangles[tri + i * 3 + 1] = face_indices[offset + i + 1] + out_triangles[tri + i * 3 + 2] = face_indices[offset + i + 2] + + +@wp.kernel(enable_backward=False) +def update_transforms(fabric_matrices: wp.fabricarray(dtype=wp.mat44d), mapping: wp.array(dtype=wp.int32), transforms: wp.array(dtype=wp.transformf)): + tid = wp.tid() + if mapping[tid] > -1: + m = fabric_matrices[mapping[tid]] + + orientation = wp.mat33f(wp.float32(m[0, 0]), wp.float32(m[1, 0]), wp.float32(m[2, 0]), + wp.float32(m[0, 1]), wp.float32(m[1, 1]), wp.float32(m[2, 1]), + wp.float32(m[0, 2]), wp.float32(m[1, 2]), wp.float32(m[2, 2])) + + position = wp.vec3f(wp.float32(m[3, 0]), wp.float32(m[3, 1]), wp.float32(m[3, 2])) + + transforms[tid] = wp.transformf(position, wp.normalize(wp.quat_from_matrix(orientation))) + + +class NewtonWarpRendererDirect: + @dataclass + class PrimData: + is_shared: bool = False + shape_type: SensorTiledCamera.RenderShapeType = SensorTiledCamera.RenderShapeType.NONE + master_prim: Usd.Prim | None = None + prims: list[tuple[int, Usd.Prim]] = field(default_factory=lambda: []) + + def __init__(self, scene: InteractiveScene): + self.prim_data: dict[str, NewtonWarpRendererDirect.PrimData] = {} + self.num_worlds = self.__collect_prims(isaaclab_sim.get_current_stage()) + + shape_transforms = [] + shape_sizes = [] + shape_types = [] + shape_mesh_indices = [] + shape_world_indices = [] + + self.__warp_meshes = [] + self.__fabric_stage_id = None + self.__fabric_selection: usdrt.RtPrimSelection = None + self.__fabric_selection_mapping: list[int] = [] + + for prim_path, prim_data in self.prim_data.items(): + if prim_data.is_shared: + mesh_index = -1 + if prim_data.shape_type == SensorTiledCamera.RenderShapeType.MESH: + mesh_index = len(self.__warp_meshes) + self.__warp_meshes.append(self.__build_mesh(prim_data.master_prim)) + + for world_id, prim in prim_data.prims: + shape_types.append(prim_data.shape_type) + shape_transforms.append(self.__resolve_transform(prim)) + shape_sizes.append(self.__resolve_shape_size(prim_data.shape_type, prim)) + shape_mesh_indices.append(mesh_index) + shape_world_indices.append(world_id) + + self.camera_manager = CameraManager(scene) + + self.render_context = SensorTiledCamera.RenderContext(self.num_worlds) + self.render_context.num_shapes_total = len(shape_transforms) + self.render_context.num_shapes_enabled = self.render_context.num_shapes_total + self.render_context.mesh_ids = wp.array([mesh.id for mesh in self.__warp_meshes], dtype=wp.uint64) + self.render_context.shape_mesh_indices = wp.array(shape_mesh_indices, dtype=wp.int32) + self.render_context.shape_types = wp.array(shape_types, dtype=wp.int32) + self.render_context.mesh_bounds = wp.empty((self.render_context.num_shapes_total, 2), dtype=wp.vec3f, ndim=2) + self.render_context.shape_enabled = wp.array(np.arange(self.render_context.num_shapes_total), dtype=wp.uint32) + self.render_context.shape_sizes = wp.array(shape_sizes, dtype=wp.vec3f) + self.render_context.shape_transforms = wp.array(shape_transforms, dtype=wp.transformf) + self.render_context.shape_materials = wp.array(np.full(self.render_context.num_shapes_total, fill_value=-1, dtype=np.int32), dtype=wp.int32) + self.render_context.shape_world_index = wp.array(shape_world_indices, dtype=wp.int32) + self.render_context.utils.compute_mesh_bounds() + self.render_context.utils.create_default_light(False) + self.render_context.utils.assign_random_colors_per_shape() + + self.camera_manager.create_outputs(self.render_context) + + def update(self): + self.__update_fabric_selection() + fabric_matrices = wp.fabricarray(self.__fabric_selection.__fabric_arrays_interface__, "omni:fabric:worldMatrix", dtype=wp.mat44d) + wp.launch(update_transforms, len(self.__fabric_selection_mapping), [fabric_matrices, wp.array(self.__fabric_selection_mapping, dtype=wp.int32), self.render_context.shape_transforms]) + + def render(self, sensor_name: str): + if camera_data := self.camera_manager.camera_data.get(sensor_name): + self.__render(camera_data) + + def render_all(self): + for name, camera_data in self.camera_manager.camera_data.items(): + self.__render(camera_data) + + def __render(self, camera_data: CameraManager.CameraData): + self.render_context.render(self.camera_manager.get_camera_transforms(camera_data), camera_data.camera_rays, camera_data.color_image) + + def __update_fabric_selection(self): + stage_id = isaaclab_sim.get_current_stage_id() + if self.__fabric_stage_id != stage_id: + self.__fabric_stage_id = stage_id + self.__fabric_selection = None + + stage = usdrt.Usd.Stage.Attach(stage_id) + + update_mapping = False + if self.__fabric_selection is None: + self.__fabric_selection = stage.SelectPrims(require_attrs=[(usdrt.Sdf.ValueTypeNames.Matrix4d, "omni:fabric:worldMatrix", usdrt.Usd.Access.Read)], want_paths=True, device=wp.get_device().alias) + update_mapping = True + else: + update_mapping = self.__fabric_selection.PrepareForReuse() + + if update_mapping: + self.__fabric_selection_mapping = [] + selection_paths = self.__fabric_selection.GetPaths() + for prim_path, prim_data in self.prim_data.items(): + if prim_data.is_shared: + for world_id, prim in prim_data.prims: + try: + self.__fabric_selection_mapping.append(selection_paths.index(prim_path % world_id)) + except ValueError: + self.__fabric_selection_mapping.append(-1) + + def __collect_prims(self, stage: Usd.Stage, env_regex: str = r"(?P/World/envs/env_)(?P\d+)(?P/.*)") -> int: + env_pattern = re.compile(env_regex) + + num_worlds = -1 + stage_prims: list[Usd.Prim] = [stage.GetPseudoRoot()] + while stage_prims: + prim = stage_prims.pop(0) + prim_path = prim.GetPath().pathString + + world_id = -1 + if match := env_pattern.match(prim_path): + world_id = int(match.group("id")) + prim_path = match.group("root") + "%d" + match.group("path") + + if world_id > -1: + if world_id > num_worlds: + num_worlds = world_id + + imageable = UsdGeom.Imageable(prim) + if imageable and imageable.ComputeVisibility() == UsdGeom.Tokens.invisible: + continue + + shape_type = SensorTiledCamera.RenderShapeType.NONE + + if prim.IsA(UsdGeom.Mesh): + shape_type = SensorTiledCamera.RenderShapeType.MESH + elif prim.IsA(UsdGeom.Sphere): + shape_type = SensorTiledCamera.RenderShapeType.SPHERE + elif prim.IsA(UsdGeom.Capsule): + shape_type = SensorTiledCamera.RenderShapeType.CAPSULE + elif prim.IsA(UsdGeom.Cube): + shape_type = SensorTiledCamera.RenderShapeType.BOX + elif prim.IsA(UsdGeom.Cylinder): + shape_type = SensorTiledCamera.RenderShapeType.CYLINDER + elif prim.IsA(UsdGeom.Cone): + shape_type = SensorTiledCamera.RenderShapeType.CONE + elif prim.IsA(UsdGeom.Plane): + shape_type = SensorTiledCamera.RenderShapeType.PLANE + + if shape_type != SensorTiledCamera.RenderShapeType.NONE: + if not prim_path in self.prim_data: + self.prim_data[prim_path] = NewtonWarpRendererDirect.PrimData(world_id > -1, shape_type, prim) + self.prim_data[prim_path].prims.append((world_id, prim)) + + if child_prims := prim.GetFilteredChildren(UsdGeom.TraverseInstanceProxies()): + stage_prims.extend(child_prims) + return num_worlds + 1 + + def __build_mesh(self, prim: Usd.Prim): + mesh = UsdGeom.Mesh(prim) + points = wp.array(mesh.GetPointsAttr().Get(), dtype=wp.vec3f) + face_vertex_counts = wp.array(mesh.GetFaceVertexCountsAttr().Get(), dtype=wp.int32) + face_vertex_indices = wp.array(mesh.GetFaceVertexIndicesAttr().Get(), dtype=wp.int32) + + num_face_counts = face_vertex_counts.size + wp_face_offsets = wp.zeros(num_face_counts + 2, dtype=wp.int32) + + wp.launch(kernel=compute_triangle_count, dim=1, inputs=[num_face_counts, face_vertex_counts, wp_face_offsets]) + + num_triangles = wp_face_offsets.numpy()[num_face_counts].item() + wp_triangle_indices = wp.empty(num_triangles * 3, dtype=wp.int32) + + wp.launch(kernel=triangulate_faces, dim=num_face_counts, inputs=[num_face_counts, face_vertex_counts, face_vertex_indices, wp_face_offsets, wp_triangle_indices]) + + return wp.Mesh(points=points, velocities=None, indices=wp_triangle_indices) + + def __resolve_transform(self, prim: Usd.Prim) -> wp.transformf: + position, orientation = isaaclab_sim.resolve_prim_pose(prim) + return wp.transformf(position, wp.quatf(orientation[1], orientation[2], orientation[3], orientation[0])) + + def __resolve_scale(self, prim: Usd.Prim) -> wp.vec3f: + scale = isaaclab_sim.resolve_prim_scale(prim) + return wp.vec3f(scale) + + def __resolve_shape_size(self, shape_type: SensorTiledCamera.RenderShapeType, prim: Usd.Prim) -> wp.vec3f: + if shape_type == SensorTiledCamera.RenderShapeType.SPHERE: + return self.__resolve_shape_size_sphere(prim) + if shape_type == SensorTiledCamera.RenderShapeType.CAPSULE: + return self.__resolve_shape_size_capsule(prim) + if shape_type == SensorTiledCamera.RenderShapeType.BOX: + return self.__resolve_shape_size_box(prim) + if shape_type == SensorTiledCamera.RenderShapeType.CYLINDER: + return self.__resolve_shape_size_cylinder(prim) + if shape_type == SensorTiledCamera.RenderShapeType.CONE: + return self.__resolve_shape_size_cone(prim) + if shape_type == SensorTiledCamera.RenderShapeType.PLANE: + return self.__resolve_shape_size_plane(prim) + return self.__resolve_scale(prim) + + def __resolve_shape_size_sphere(self, prim: Usd.Prim) -> wp.vec3f: + sphere = UsdGeom.Sphere(prim) + radius = sphere.GetRadiusAttr().Get() + return wp.vec3f(radius, 0.0, 0.0) + + def __resolve_shape_size_capsule(self, prim: Usd.Prim) -> wp.vec3f: + capsule = UsdGeom.Capsule(prim) + radius = capsule.GetRadiusAttr().Get() + height = capsule.GetHeightAttr().Get() + return wp.vec3f(radius, height, 0.0) + + def __resolve_shape_size_box(self, prim: Usd.Prim) -> wp.vec3f: + cube = UsdGeom.Cube(prim) + size = cube.GetSizeAttr().Get() + scale = self.__resolve_scale(prim) + return wp.vec3f(size * scale[0], size * scale[1], size * scale[2]) + + def __resolve_shape_size_cylinder(self, prim: Usd.Prim) -> wp.vec3f: + cylinder = UsdGeom.Cylinder(prim) + radius = cylinder.GetRadiusAttr().Get() + height = cylinder.GetHeightAttr().Get() + return wp.vec3f(radius, height, 0.0) + + def __resolve_shape_size_cone(self, prim: Usd.Prim) -> wp.vec3f: + cone = UsdGeom.Cone(prim) + radius = cone.GetRadiusAttr().Get() + height = cone.GetHeightAttr().Get() + return wp.vec3f(radius, height, 0.0) + + def __resolve_shape_size_plane(self, prim: Usd.Prim) -> wp.vec3f: + return wp.vec3f(0.0) diff --git a/source/isaaclab/isaaclab/sim/scene_data_providers/newton_scene_data_provider.py b/source/isaaclab/isaaclab/sim/scene_data_providers/newton_scene_data_provider.py index 43814c48551..f1f061ff609 100644 --- a/source/isaaclab/isaaclab/sim/scene_data_providers/newton_scene_data_provider.py +++ b/source/isaaclab/isaaclab/sim/scene_data_providers/newton_scene_data_provider.py @@ -94,6 +94,14 @@ def get_contacts(self) -> dict[str, Any] | None: except Exception: return None - def get_mesh_data(self) -> dict[str, Any] | None: - """ADAPTED: Extract mesh data from Newton shapes (future work).""" + def get_camera_data(self) -> dict[str, Any] | None: + """UNAVAILABLE: Newton backend doesn't provide USD cameras.""" + return None + + def get_camera_transforms(self) -> dict[str, Any] | None: + """UNAVAILABLE: Newton backend doesn't provide USD cameras.""" + return None + + def get_camera_configs(self) -> list[dict[str, Any]] | None: + """UNAVAILABLE: Newton backend doesn't provide USD camera configs.""" return None diff --git a/source/isaaclab/isaaclab/sim/scene_data_providers/ov_scene_data_provider.py b/source/isaaclab/isaaclab/sim/scene_data_providers/ov_scene_data_provider.py index 100ff7f0b10..9e541be8f8d 100644 --- a/source/isaaclab/isaaclab/sim/scene_data_providers/ov_scene_data_provider.py +++ b/source/isaaclab/isaaclab/sim/scene_data_providers/ov_scene_data_provider.py @@ -15,7 +15,15 @@ class OVSceneDataProvider: - """Scene data provider for Omni PhysX backend.""" + """Scene data provider for Omni PhysX backend. + + Supports: + - body poses via PhysX tensor views, with XformPrimView fallback + - camera poses & intrinsics + - USD stage handles + - Newton model/state handles + - TODO: mesh data access + """ def __init__(self, visualizer_cfgs: list[Any] | None, stage, simulation_context) -> None: from isaacsim.core.simulation_manager import SimulationManager @@ -27,25 +35,11 @@ def __init__(self, visualizer_cfgs: list[Any] | None, stage, simulation_context) self._rigid_body_view = None self._articulation_view = None self._xform_views: dict[str, Any] = {} - self._body_key_index_map: dict[str, int] = {} self._view_body_index_map: dict[str, list[int]] = {} - # Determine which visualizers need Newton state sync - self._has_newton_visualizer = False - self._has_rerun_visualizer = False - self._has_ov_visualizer = False - if visualizer_cfgs: - for cfg in visualizer_cfgs: - viz_type = getattr(cfg, "visualizer_type", None) - if viz_type == "newton": - self._has_newton_visualizer = True - elif viz_type == "rerun": - self._has_rerun_visualizer = True - elif viz_type == "omniverse": - self._has_ov_visualizer = True - + viz_types = {getattr(cfg, "visualizer_type", None) for cfg in (visualizer_cfgs or [])} # Explicit mode flag for Newton synchronization - self._needs_newton_sync = self._has_newton_visualizer or self._has_rerun_visualizer + self._needs_newton_sync = bool({"newton", "rerun"} & viz_types) self._metadata = { "physics_backend": "omni", @@ -57,6 +51,7 @@ def __init__(self, visualizer_cfgs: list[Any] | None, stage, simulation_context) self._device = getattr(self._simulation_context, "device", "cuda:0") self._newton_model = None self._newton_state = None + self._camera_data_cache: dict[str, Any] | None = None self._rigid_body_paths: list[str] = [] self._articulation_paths: list[str] = [] self._set_body_q_kernel = None @@ -71,44 +66,36 @@ def __init__(self, visualizer_cfgs: list[Any] | None, stage, simulation_context) logger.info("[OVSceneDataProvider] OV visualizer only - skipping Newton model build") def _get_num_envs(self) -> int: - try: - import carb + """Read num_envs from settings; returns 0 if unset/unavailable.""" + import carb - carb_settings_iface = carb.settings.get_settings() - num_envs = carb_settings_iface.get("/isaaclab/scene/num_envs") - if num_envs: - return int(num_envs) - except Exception: - return 0 - return 0 + carb_settings_iface = carb.settings.get_settings() + num_envs = carb_settings_iface.get("/isaaclab/scene/num_envs") + return int(num_envs) if num_envs else 0 @staticmethod def _wildcard_env_paths(paths: list[str]) -> list[str]: - wildcard_paths = [] - for path in paths: - if "/World/envs/env_0" in path: - wildcard_paths.append(path.replace("/World/envs/env_0", "/World/envs/env_*")) + """Convert /World/envs/env_0 paths to a wildcard pattern when possible.""" + wildcard_paths = [ + path.replace("/World/envs/env_0", "/World/envs/env_*") for path in paths if "/World/envs/env_0" in path + ] return list(dict.fromkeys(wildcard_paths)) if wildcard_paths else paths def _refresh_newton_model_if_needed(self) -> None: + """Rebuild Newton model/state and PhysX views if env count changes.""" num_envs = self._get_num_envs() if num_envs <= 0: return - if self._newton_model is None or self._newton_state is None: + needs_rebuild = self._newton_model is None or self._newton_state is None + needs_rebuild = needs_rebuild or (self._metadata.get("num_envs", 0) != num_envs) + if needs_rebuild: self._build_newton_model_from_usd() self._setup_rigid_body_view() self._setup_articulation_view() - return - - if self._metadata.get("num_envs", 0) != num_envs: - self._build_newton_model_from_usd() - self._setup_rigid_body_view() - self._setup_articulation_view() - return def _build_newton_model_from_usd(self) -> None: - """Build Newton model from USD and extract scene structure.""" + """Build Newton model from USD and cache body/articulation paths.""" try: from newton import ModelBuilder @@ -122,7 +109,6 @@ def _build_newton_model_from_usd(self) -> None: self._articulation_paths = list(self._newton_model.articulation_key) self._xform_views.clear() - self._body_key_index_map = {path: i for i, path in enumerate(self._rigid_body_paths)} self._view_body_index_map = {} except ModuleNotFoundError as exc: logger.error( @@ -169,10 +155,12 @@ def _setup_articulation_view(self) -> None: self._articulation_view = None def _get_view_world_poses(self, view): - """Read world poses from PhysX tensor API view (ArticulationView or RigidBodyView). + """Read world poses from a PhysX view. - Tries multiple method names for compatibility across PhysX API versions. - Returns (positions, orientations) tuple or (None, None) if unavailable. + Tries multiple method names for compatibility and returns + (positions, orientations) or (None, None). The returned tensors + are expected to be shaped [..., 3] and [..., 4] (xyzw or wxyz + depending on source). """ if view is None: return None, None @@ -214,13 +202,14 @@ def split_env(path: str) -> tuple[int | None, str]: match = re.search(r"/World/envs/env_(\d+)(/.*)", path) return (int(match.group(1)), match.group(2)) if match else (None, path) - # Build map: (env_id, relative_path) -> view_index + # Build map: (env_id, relative_path) -> view_index to align view order. view_map: dict[tuple[int | None, str], int] = {} for view_idx, path in enumerate(prim_paths): env_id, rel = split_env(path) view_map[(env_id, rel)] = view_idx - # Build reordering: newton_body_index -> view_index + # Build reordering: newton_body_index -> view_index so we can scatter + # PhysX view outputs into Newton body ordering. order: list[int | None] = [None] * len(self._rigid_body_paths) for body_idx, path in enumerate(self._rigid_body_paths): env_id, rel = split_env(path) @@ -233,6 +222,7 @@ def split_env(path: str) -> tuple[int | None, str]: self._view_body_index_map[key] = order # type: ignore[arg-type] def _get_view_velocities(self, view): + """Read linear/angular velocities from a PhysX view.""" if view is None: return None, None @@ -258,7 +248,7 @@ def _get_view_velocities(self, view): return None, None def _apply_view_poses(self, view: Any, view_key: str, positions: Any, orientations: Any, covered: Any) -> int: - """Read poses from a PhysX view and write uncovered bodies to output tensors.""" + """Fill poses from a PhysX view for bodies not yet covered.""" import torch if view is None: @@ -275,6 +265,7 @@ def _apply_view_poses(self, view: Any, view_key: str, positions: Any, orientatio pos = pos.to(device=self._device, dtype=torch.float32) quat = quat.to(device=self._device, dtype=torch.float32) + # Scatter view outputs into the canonical Newton body order. count = 0 for newton_idx, view_idx in enumerate(order): if view_idx is not None and not covered[newton_idx]: @@ -286,7 +277,10 @@ def _apply_view_poses(self, view: Any, view_key: str, positions: Any, orientatio return count def _apply_xform_poses(self, positions: Any, orientations: Any, covered: Any, xform_mask: Any) -> int: - """Use XformPrimView fallback for remaining uncovered bodies.""" + """Fill remaining poses using XformPrimView (USD fallback). + + This is slower but more robust when PhysX views don't cover all bodies. + """ import torch from isaaclab.sim.views import XformPrimView @@ -295,6 +289,7 @@ def _apply_xform_poses(self, positions: Any, orientations: Any, covered: Any, xf if not uncovered: return 0 + # Query each uncovered prim path directly from USD. count = 0 for idx in uncovered: path = self._rigid_body_paths[idx] @@ -317,7 +312,7 @@ def _apply_xform_poses(self, positions: Any, orientations: Any, covered: Any, xf return count def _convert_xform_quats(self, orientations: Any, xform_mask: Any) -> Any: - """Convert XformPrimView quaternions from wxyz to xyzw where needed.""" + """Convert XformPrimView quaternions from wxyz to xyzw for flagged indices.""" if not xform_mask.any(): return orientations @@ -332,7 +327,7 @@ def _convert_xform_quats(self, orientations: Any, xform_mask: Any) -> Any: return orientations_xyzw def _read_poses_from_best_source(self) -> tuple[Any, Any, str, Any] | None: - """Merge pose data from ArticulationView, RigidBodyView, and XformPrimView.""" + """Merge pose data from articulation, rigid-body, and xform views.""" if self._newton_state is None or not self._rigid_body_paths: return None @@ -343,24 +338,38 @@ def _read_poses_from_best_source(self) -> tuple[Any, Any, str, Any] | None: logger.warning(f"Body count mismatch: body_key={num_bodies}, state={self._newton_state.body_q.shape[0]}") return None + # Allocate outputs in Newton body order. positions = torch.zeros((num_bodies, 3), dtype=torch.float32, device=self._device) orientations = torch.zeros((num_bodies, 4), dtype=torch.float32, device=self._device) covered = torch.zeros(num_bodies, dtype=torch.bool, device=self._device) xform_mask = torch.zeros(num_bodies, dtype=torch.bool, device=self._device) - artic = self._apply_view_poses(self._articulation_view, "articulation_view", positions, orientations, covered) - rigid = self._apply_view_poses(self._rigid_body_view, "rigid_body_view", positions, orientations, covered) - xform = self._apply_xform_poses(positions, orientations, covered, xform_mask) + # Apply sources in preferred order: articulation, rigid bodies, then USD fallback. + articulation_count = self._apply_view_poses( + self._articulation_view, "articulation_view", positions, orientations, covered + ) + rigid_count = self._apply_view_poses( + self._rigid_body_view, "rigid_body_view", positions, orientations, covered + ) + xform_count = self._apply_xform_poses(positions, orientations, covered, xform_mask) if not covered.all(): logger.warning(f"Failed to read {(~covered).sum().item()}/{num_bodies} body poses") return None - active = sum([artic > 0, rigid > 0, xform > 0]) + active = sum([articulation_count > 0, rigid_count > 0, xform_count > 0]) source = ( "merged" if active > 1 - else ("articulation_view" if artic else "rigid_body_view" if rigid else "xform_view" if xform else "none") + else ( + "articulation_view" + if articulation_count + else "rigid_body_view" + if rigid_count + else "xform_view" + if xform_count + else "none" + ) ) return positions, orientations, source, xform_mask @@ -422,21 +431,49 @@ def update(self) -> None: logger.debug(f"Failed to sync transforms to Newton: {exc}") def get_newton_model(self) -> Any | None: + """Return Newton model when sync is enabled.""" return self._newton_model if self._needs_newton_sync else None def get_newton_state(self) -> Any | None: + """Return Newton state when sync is enabled.""" return self._newton_state if self._needs_newton_sync else None def get_usd_stage(self) -> Any: + """Return the USD stage handle.""" return self._stage - def get_mesh_data(self) -> dict[str, Any] | None: - return None + def get_camera_data(self) -> dict[str, Any] | None: + """Return cached camera discovery data from the stage.""" + if self._stage is None: + return None + if self._camera_data_cache is None: + self._camera_data_cache = self._collect_camera_data(self._stage) + return dict(self._camera_data_cache) + + def get_camera_transforms(self) -> dict[str, Any] | None: + """Return per-camera, per-env transforms (positions, orientations).""" + if self._stage is None: + return None + camera_data = self.get_camera_data() + if not camera_data: + return None + return self._collect_camera_transforms(self._stage, camera_data) + + def get_camera_configs(self) -> list[dict[str, Any]] | None: + """Return camera intrinsics/configs for discovered cameras.""" + if self._stage is None: + return None + camera_data = self.get_camera_data() + if not camera_data: + return None + return self._collect_camera_configs(self._stage, camera_data) def get_metadata(self) -> dict[str, Any]: + """Return backend metadata (num_envs, gravity, etc.).""" return dict(self._metadata) def get_transforms(self) -> dict[str, Any] | None: + """Return merged body transforms from available PhysX views.""" try: result = self._read_poses_from_best_source() if result is None: @@ -449,6 +486,7 @@ def get_transforms(self) -> dict[str, Any] | None: return None def get_velocities(self) -> dict[str, Any] | None: + """Return linear/angular velocities from available PhysX views.""" for source, view in ( ("articulation_view", self._articulation_view), ("rigid_body_view", self._rigid_body_view), @@ -461,3 +499,103 @@ def get_velocities(self) -> dict[str, Any] | None: def get_contacts(self) -> dict[str, Any] | None: """Contacts not yet supported for OV backend.""" return None + + @staticmethod + def _collect_camera_data(stage, env_regex: str = r"(?P/World/envs/env_)(?P\d+)(?P/.*)"): + """Collect camera prims across envs and build shared templates.""" + from pxr import UsdGeom + + env_pattern = re.compile(env_regex) + shared_paths: list[str] = [] + instances: dict[str, list[tuple[int, str]]] = {} + num_envs = -1 + + stage_prims: list = [stage.GetPseudoRoot()] + while stage_prims: + prim = stage_prims.pop(0) + prim_path = prim.GetPath().pathString + + world_id = 0 + template_path = prim_path + if match := env_pattern.match(prim_path): + world_id = int(match.group("id")) + template_path = match.group("root") + "%d" + match.group("path") + if world_id > num_envs: + num_envs = world_id + + imageable = UsdGeom.Imageable(prim) + if imageable and imageable.ComputeVisibility() == UsdGeom.Tokens.invisible: + continue + + if prim.IsA(UsdGeom.Camera): + if template_path not in instances: + instances[template_path] = [] + instances[template_path].append((world_id, prim_path)) + if template_path not in shared_paths: + shared_paths.append(template_path) + + if child_prims := prim.GetFilteredChildren(UsdGeom.TraverseInstanceProxies()): + stage_prims.extend(child_prims) + + return {"shared_paths": shared_paths, "instances": instances, "num_envs": num_envs + 1} + + @staticmethod + def _collect_camera_transforms(stage, camera_data: dict[str, Any]): + """Resolve camera transforms for each shared path and env.""" + import isaaclab.sim as isaaclab_sim + + shared_paths = camera_data.get("shared_paths") or [] + instances = camera_data.get("instances") or {} + num_envs = camera_data.get("num_envs", 0) + + positions: list[list[list[float] | None]] = [] + orientations: list[list[list[float] | None]] = [] + + for template_path in shared_paths: + per_world_pos: list[list[float] | None] = [None] * num_envs + per_world_ori: list[list[float] | None] = [None] * num_envs + for world_id, prim_path in instances.get(template_path, []): + if world_id < 0 or world_id >= num_envs: + continue + prim = stage.GetPrimAtPath(prim_path) + if not prim.IsValid(): + continue + pos, ori = isaaclab_sim.resolve_prim_pose(prim) + per_world_pos[world_id] = [float(pos[0]), float(pos[1]), float(pos[2])] + per_world_ori[world_id] = [float(ori[0]), float(ori[1]), float(ori[2]), float(ori[3])] + positions.append(per_world_pos) + orientations.append(per_world_ori) + + return {"order": shared_paths, "positions": positions, "orientations": orientations, "num_envs": num_envs} + + @staticmethod + def _collect_camera_configs(stage, camera_data: dict[str, Any]) -> list[dict[str, Any]]: + """Read camera intrinsics from one instance per shared path.""" + from pxr import UsdGeom + + shared_paths = camera_data.get("shared_paths") or [] + instances = camera_data.get("instances") or {} + + configs: list[dict[str, Any]] = [] + for template_path in shared_paths: + prim_path = None + for _, instance_path in instances.get(template_path, []): + prim_path = instance_path + break + if not prim_path: + continue + prim = stage.GetPrimAtPath(prim_path) + if not prim.IsValid(): + continue + camera = UsdGeom.Camera(prim) + configs.append( + { + "template_path": template_path, + "prim_path": prim_path, + "focal_length": float(camera.GetFocalLengthAttr().Get()), + "horizontal_aperture": float(camera.GetHorizontalApertureAttr().Get()), + "vertical_aperture": float(camera.GetVerticalApertureAttr().Get()), + "clipping_range": tuple(camera.GetClippingRangeAttr().Get()), + } + ) + return configs diff --git a/source/isaaclab/isaaclab/sim/scene_data_providers/scene_data_provider.py b/source/isaaclab/isaaclab/sim/scene_data_providers/scene_data_provider.py index 14708219c2d..62a260da240 100644 --- a/source/isaaclab/isaaclab/sim/scene_data_providers/scene_data_provider.py +++ b/source/isaaclab/isaaclab/sim/scene_data_providers/scene_data_provider.py @@ -80,7 +80,17 @@ def get_contacts(self) -> dict[str, Any] | None: return None return self._provider.get_contacts() - def get_mesh_data(self) -> dict[str, Any] | None: + def get_camera_data(self) -> dict[str, Any] | None: if self._provider is None: return None - return self._provider.get_mesh_data() + return self._provider.get_camera_data() + + def get_camera_transforms(self) -> dict[str, Any] | None: + if self._provider is None: + return None + return self._provider.get_camera_transforms() + + def get_camera_configs(self) -> list[dict[str, Any]] | None: + if self._provider is None: + return None + return self._provider.get_camera_configs() diff --git a/source/isaaclab/setup.py b/source/isaaclab/setup.py index c8a68b01797..0a13ee19935 100644 --- a/source/isaaclab/setup.py +++ b/source/isaaclab/setup.py @@ -38,7 +38,7 @@ "mujoco>=3.4.0.dev839962392", "mujoco-warp>=0.0.1", "cbor2>=5.7.0", - "newton>=0.2.1", + "newton @ git+https://github.com/newton-physics/newton.git@d435c418b6510f628fbb613736e2cfa4ad7968f3", "imgui-bundle>=1.92.0", "PyOpenGL-accelerate==3.1.10", "matplotlib>=3.10.3", # minimum version for Python 3.12 support diff --git a/source/isaaclab_tasks/test/benchmarking/configs_custom_reward_thresholds.yaml b/source/isaaclab_tasks/test/benchmarking/configs_custom_reward_thresholds.yaml index cb899cd591b..abe28337b3a 100644 --- a/source/isaaclab_tasks/test/benchmarking/configs_custom_reward_thresholds.yaml +++ b/source/isaaclab_tasks/test/benchmarking/configs_custom_reward_thresholds.yaml @@ -1,3 +1,8 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + custom_rewards: rl_games:Isaac-Dexsuite-Kuka-Allegro-Lift-v0: max_iterations: 2000 From 2dda78530a803998406b07cc6946ac3bd0cc512d Mon Sep 17 00:00:00 2001 From: Matthew Trepte Date: Fri, 6 Feb 2026 02:43:35 +0000 Subject: [PATCH 42/46] clean --- .../isaaclab/isaaclab/renderers/__init__.py | 5 + .../renderers/newton_warp_renderer.py | 64 ++++++-- .../renderers/newton_warp_renderer_direct.py | 90 ++++++++--- .../newton_scene_data_provider.py | 85 +++-------- .../ov_scene_data_provider.py | 140 +++++------------- .../scene_data_provider.py | 98 ++++-------- .../isaaclab/sim/simulation_context.py | 17 ++- .../isaaclab/visualizers/newton_visualizer.py | 20 +-- .../isaaclab/visualizers/ov_visualizer.py | 15 +- .../isaaclab/visualizers/rerun_visualizer.py | 20 +-- .../isaaclab/visualizers/visualizer.py | 7 +- 11 files changed, 256 insertions(+), 305 deletions(-) diff --git a/source/isaaclab/isaaclab/renderers/__init__.py b/source/isaaclab/isaaclab/renderers/__init__.py index 55a51a7e2b5..1d73e820b42 100644 --- a/source/isaaclab/isaaclab/renderers/__init__.py +++ b/source/isaaclab/isaaclab/renderers/__init__.py @@ -1 +1,6 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + from .newton_warp_renderer import NewtonWarpRenderer diff --git a/source/isaaclab/isaaclab/renderers/newton_warp_renderer.py b/source/isaaclab/isaaclab/renderers/newton_warp_renderer.py index 45ca31655a1..19639fd8e9f 100644 --- a/source/isaaclab/isaaclab/renderers/newton_warp_renderer.py +++ b/source/isaaclab/isaaclab/renderers/newton_warp_renderer.py @@ -1,14 +1,19 @@ -from isaaclab.utils.math import convert_camera_frame_orientation_convention -from isaaclab.scene import InteractiveScene -from isaaclab.sensors import TiledCamera -import isaaclab.sim as isaaclab_sim +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause +import os from dataclasses import dataclass, field -from pxr import Usd import newton import warp as wp -import os + +from pxr import Usd + +import isaaclab.sim as isaaclab_sim +from isaaclab.scene import InteractiveScene +from isaaclab.sensors import TiledCamera class CameraManager: @@ -25,7 +30,7 @@ def __init__(self, scene: InteractiveScene): self.scene = scene self.num_cameras = 1 self.camera_data: dict[str, CameraManager.CameraData] = {} - + for name, sensor in self.scene.sensors.items(): camera_data = CameraManager.CameraData() camera_data.prims = isaaclab_sim.find_matching_prims(sensor.cfg.prim_path) @@ -38,23 +43,30 @@ def create_outputs(self, render_context: newton.sensors.SensorTiledCamera.Render self.render_context = render_context for name in self.scene.sensors: camera_fovs = wp.array([20.0] * self.num_cameras, dtype=wp.float32) - self.camera_data[name].camera_rays = render_context.utils.compute_pinhole_camera_rays(self.camera_data[name].width, self.camera_data[name].height, camera_fovs) - self.camera_data[name].color_image = render_context.create_color_image_output(self.camera_data[name].width, self.camera_data[name].height, self.num_cameras) - + width = self.camera_data[name].width + height = self.camera_data[name].height + self.camera_data[name].camera_rays = render_context.utils.compute_pinhole_camera_rays( + width, height, camera_fovs + ) + self.camera_data[name].color_image = render_context.create_color_image_output( + width, height, self.num_cameras + ) + def get_camera_transforms(self, camera_data: CameraData) -> wp.array(dtype=wp.transformf): camera_transforms = [] for prim in camera_data.prims: camera_transforms.append(self.__resolve_camera_transform(prim)) return wp.array([camera_transforms], dtype=wp.transformf) - + def save_images(self, filename: str): if self.render_context is None: return for name, camera_data in self.camera_data.items(): color_data = self.render_context.utils.flatten_color_image_to_rgba(camera_data.color_image) - + from PIL import Image + os.makedirs(os.path.dirname(filename), exist_ok=True) Image.fromarray(color_data.numpy()).save(filename % name) @@ -96,7 +108,12 @@ def update(self): if mapping := self.physx_to_newton_body_mapping.get(name): physx_pos = wp.from_torch(articulation.data.body_pos_w) physx_quat = wp.from_torch(articulation.data.body_quat_w) - wp.launch(NewtonWarpRenderer.__update_transforms, mapping.shape, [mapping, self.newton_model.body_world, physx_pos, physx_quat, self.newton_state.body_q]) + inputs = [mapping, self.newton_model.body_world, physx_pos, physx_quat, self.newton_state.body_q] + wp.launch( + NewtonWarpRenderer.__update_transforms, + mapping.shape, + inputs, + ) def render(self, sensor_name: str): if camera_data := self.camera_manager.camera_data.get(sensor_name): @@ -107,7 +124,13 @@ def render_all(self): self.__render(camera_data) def __render(self, camera_data: CameraManager.CameraData): - self.newton_sensor.render(self.newton_state, self.camera_manager.get_camera_transforms(camera_data), camera_data.camera_rays, camera_data.color_image) + camera_transforms = self.camera_manager.get_camera_transforms(camera_data) + self.newton_sensor.render( + self.newton_state, + camera_transforms, + camera_data.camera_rays, + camera_data.color_image, + ) def __update_mapping(self): if self.physx_to_newton_body_mapping: @@ -122,10 +145,19 @@ def __update_mapping(self): prim_path = prim.GetPath().AppendChild(body_name).pathString body_indices.append(self.newton_model.body_key.index(prim_path)) articulation_mapping.append(body_indices) - self.physx_to_newton_body_mapping[name] = wp.array(articulation_mapping, dtype=wp.int32) + self.physx_to_newton_body_mapping[name] = wp.array( + articulation_mapping, + dtype=wp.int32, + ) @wp.kernel(enable_backward=False) - def __update_transforms(mapping: wp.array(dtype=wp.int32, ndim=2), newton_body_world: wp.array(dtype=wp.int32), physx_pos: wp.array(dtype=wp.float32, ndim=3), physx_quat: wp.array(dtype=wp.float32, ndim=3), out_transform: wp.array(dtype=wp.transformf)): + def __update_transforms( + mapping: wp.array(dtype=wp.int32, ndim=2), + newton_body_world: wp.array(dtype=wp.int32), + physx_pos: wp.array(dtype=wp.float32, ndim=3), + physx_quat: wp.array(dtype=wp.float32, ndim=3), + out_transform: wp.array(dtype=wp.transformf), + ): physx_world_id, physx_body_id = wp.tid() newton_body_index = mapping[physx_world_id, physx_body_id] diff --git a/source/isaaclab/isaaclab/renderers/newton_warp_renderer_direct.py b/source/isaaclab/isaaclab/renderers/newton_warp_renderer_direct.py index 1aebac7dd27..dfccbb15e28 100644 --- a/source/isaaclab/isaaclab/renderers/newton_warp_renderer_direct.py +++ b/source/isaaclab/isaaclab/renderers/newton_warp_renderer_direct.py @@ -1,19 +1,27 @@ -from isaaclab.scene import InteractiveScene -import isaaclab.sim as isaaclab_sim +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause +import re from dataclasses import dataclass, field -from pxr import Usd, UsdGeom -from newton.sensors import SensorTiledCamera import numpy as np import warp as wp +from newton.sensors import SensorTiledCamera + import usdrt -import re +from pxr import Usd, UsdGeom +import isaaclab.sim as isaaclab_sim from isaaclab.renderers.newton_warp_renderer import CameraManager +from isaaclab.scene import InteractiveScene + @wp.kernel(enable_backward=False) -def compute_triangle_count(num_face_counts: wp.int32, face_counts: wp.array(dtype=wp.int32), out_face_offsets: wp.array(dtype=wp.int32)): +def compute_triangle_count( + num_face_counts: wp.int32, face_counts: wp.array(dtype=wp.int32), out_face_offsets: wp.array(dtype=wp.int32) +): offset = wp.int32(0) for i in range(num_face_counts): out_face_offsets[i] = offset @@ -22,7 +30,13 @@ def compute_triangle_count(num_face_counts: wp.int32, face_counts: wp.array(dtyp @wp.kernel(enable_backward=False) -def triangulate_faces(num_face_counts: wp.int32, face_counts: wp.array(dtype=wp.int32), face_indices: wp.array(dtype=wp.int32), face_offsets: wp.array(dtype=wp.int32), out_triangles: wp.array(dtype=wp.int32)): +def triangulate_faces( + num_face_counts: wp.int32, + face_counts: wp.array(dtype=wp.int32), + face_indices: wp.array(dtype=wp.int32), + face_offsets: wp.array(dtype=wp.int32), + out_triangles: wp.array(dtype=wp.int32), +): offset = face_offsets[wp.tid()] num_triangles = face_counts[wp.tid()] - 2 tri = wp.atomic_add(face_offsets, num_face_counts + 1, num_triangles * 3) @@ -34,14 +48,26 @@ def triangulate_faces(num_face_counts: wp.int32, face_counts: wp.array(dtype=wp. @wp.kernel(enable_backward=False) -def update_transforms(fabric_matrices: wp.fabricarray(dtype=wp.mat44d), mapping: wp.array(dtype=wp.int32), transforms: wp.array(dtype=wp.transformf)): +def update_transforms( + fabric_matrices: wp.fabricarray(dtype=wp.mat44d), + mapping: wp.array(dtype=wp.int32), + transforms: wp.array(dtype=wp.transformf), +): tid = wp.tid() if mapping[tid] > -1: m = fabric_matrices[mapping[tid]] - orientation = wp.mat33f(wp.float32(m[0, 0]), wp.float32(m[1, 0]), wp.float32(m[2, 0]), - wp.float32(m[0, 1]), wp.float32(m[1, 1]), wp.float32(m[2, 1]), - wp.float32(m[0, 2]), wp.float32(m[1, 2]), wp.float32(m[2, 2])) + orientation = wp.mat33f( + wp.float32(m[0, 0]), + wp.float32(m[1, 0]), + wp.float32(m[2, 0]), + wp.float32(m[0, 1]), + wp.float32(m[1, 1]), + wp.float32(m[2, 1]), + wp.float32(m[0, 2]), + wp.float32(m[1, 2]), + wp.float32(m[2, 2]), + ) position = wp.vec3f(wp.float32(m[3, 0]), wp.float32(m[3, 1]), wp.float32(m[3, 2])) @@ -97,7 +123,9 @@ def __init__(self, scene: InteractiveScene): self.render_context.shape_enabled = wp.array(np.arange(self.render_context.num_shapes_total), dtype=wp.uint32) self.render_context.shape_sizes = wp.array(shape_sizes, dtype=wp.vec3f) self.render_context.shape_transforms = wp.array(shape_transforms, dtype=wp.transformf) - self.render_context.shape_materials = wp.array(np.full(self.render_context.num_shapes_total, fill_value=-1, dtype=np.int32), dtype=wp.int32) + self.render_context.shape_materials = wp.array( + np.full(self.render_context.num_shapes_total, fill_value=-1, dtype=np.int32), dtype=wp.int32 + ) self.render_context.shape_world_index = wp.array(shape_world_indices, dtype=wp.int32) self.render_context.utils.compute_mesh_bounds() self.render_context.utils.create_default_light(False) @@ -107,8 +135,18 @@ def __init__(self, scene: InteractiveScene): def update(self): self.__update_fabric_selection() - fabric_matrices = wp.fabricarray(self.__fabric_selection.__fabric_arrays_interface__, "omni:fabric:worldMatrix", dtype=wp.mat44d) - wp.launch(update_transforms, len(self.__fabric_selection_mapping), [fabric_matrices, wp.array(self.__fabric_selection_mapping, dtype=wp.int32), self.render_context.shape_transforms]) + fabric_matrices = wp.fabricarray( + self.__fabric_selection.__fabric_arrays_interface__, "omni:fabric:worldMatrix", dtype=wp.mat44d + ) + wp.launch( + update_transforms, + len(self.__fabric_selection_mapping), + [ + fabric_matrices, + wp.array(self.__fabric_selection_mapping, dtype=wp.int32), + self.render_context.shape_transforms, + ], + ) def render(self, sensor_name: str): if camera_data := self.camera_manager.camera_data.get(sensor_name): @@ -119,7 +157,9 @@ def render_all(self): self.__render(camera_data) def __render(self, camera_data: CameraManager.CameraData): - self.render_context.render(self.camera_manager.get_camera_transforms(camera_data), camera_data.camera_rays, camera_data.color_image) + self.render_context.render( + self.camera_manager.get_camera_transforms(camera_data), camera_data.camera_rays, camera_data.color_image + ) def __update_fabric_selection(self): stage_id = isaaclab_sim.get_current_stage_id() @@ -131,7 +171,11 @@ def __update_fabric_selection(self): update_mapping = False if self.__fabric_selection is None: - self.__fabric_selection = stage.SelectPrims(require_attrs=[(usdrt.Sdf.ValueTypeNames.Matrix4d, "omni:fabric:worldMatrix", usdrt.Usd.Access.Read)], want_paths=True, device=wp.get_device().alias) + self.__fabric_selection = stage.SelectPrims( + require_attrs=[(usdrt.Sdf.ValueTypeNames.Matrix4d, "omni:fabric:worldMatrix", usdrt.Usd.Access.Read)], + want_paths=True, + device=wp.get_device().alias, + ) update_mapping = True else: update_mapping = self.__fabric_selection.PrepareForReuse() @@ -147,7 +191,9 @@ def __update_fabric_selection(self): except ValueError: self.__fabric_selection_mapping.append(-1) - def __collect_prims(self, stage: Usd.Stage, env_regex: str = r"(?P/World/envs/env_)(?P\d+)(?P/.*)") -> int: + def __collect_prims( + self, stage: Usd.Stage, env_regex: str = r"(?P/World/envs/env_)(?P\d+)(?P/.*)" + ) -> int: env_pattern = re.compile(env_regex) num_worlds = -1 @@ -170,7 +216,7 @@ def __collect_prims(self, stage: Usd.Stage, env_regex: str = r"(?P/World/e continue shape_type = SensorTiledCamera.RenderShapeType.NONE - + if prim.IsA(UsdGeom.Mesh): shape_type = SensorTiledCamera.RenderShapeType.MESH elif prim.IsA(UsdGeom.Sphere): @@ -187,7 +233,7 @@ def __collect_prims(self, stage: Usd.Stage, env_regex: str = r"(?P/World/e shape_type = SensorTiledCamera.RenderShapeType.PLANE if shape_type != SensorTiledCamera.RenderShapeType.NONE: - if not prim_path in self.prim_data: + if prim_path not in self.prim_data: self.prim_data[prim_path] = NewtonWarpRendererDirect.PrimData(world_id > -1, shape_type, prim) self.prim_data[prim_path].prims.append((world_id, prim)) @@ -209,7 +255,11 @@ def __build_mesh(self, prim: Usd.Prim): num_triangles = wp_face_offsets.numpy()[num_face_counts].item() wp_triangle_indices = wp.empty(num_triangles * 3, dtype=wp.int32) - wp.launch(kernel=triangulate_faces, dim=num_face_counts, inputs=[num_face_counts, face_vertex_counts, face_vertex_indices, wp_face_offsets, wp_triangle_indices]) + wp.launch( + kernel=triangulate_faces, + dim=num_face_counts, + inputs=[num_face_counts, face_vertex_counts, face_vertex_indices, wp_face_offsets, wp_triangle_indices], + ) return wp.Mesh(points=points, velocities=None, indices=wp_triangle_indices) diff --git a/source/isaaclab/isaaclab/sim/scene_data_providers/newton_scene_data_provider.py b/source/isaaclab/isaaclab/sim/scene_data_providers/newton_scene_data_provider.py index f1f061ff609..54564cbd2df 100644 --- a/source/isaaclab/isaaclab/sim/scene_data_providers/newton_scene_data_provider.py +++ b/source/isaaclab/isaaclab/sim/scene_data_providers/newton_scene_data_provider.py @@ -3,105 +3,54 @@ # # SPDX-License-Identifier: BSD-3-Clause -"""Newton-backed scene data provider.""" +"""Newton-backed scene data provider (stub).""" from __future__ import annotations -import logging from typing import Any -logger = logging.getLogger(__name__) - class NewtonSceneDataProvider: """Scene data provider for Newton Warp physics backend. - Native (cheap): Newton Model/State from NewtonManager - Adapted (future): USD stage (would need Newton→USD sync for OV visualizer) + This stub exists to keep the interface stable while the Newton provider is + implemented. All optional data accessors return None. """ def __init__(self, visualizer_cfgs: list[Any] | None) -> None: - self._has_ov_visualizer = False - self._metadata: dict[str, Any] = {} - - if visualizer_cfgs: - for cfg in visualizer_cfgs: - if getattr(cfg, "visualizer_type", None) == "omniverse": - self._has_ov_visualizer = True - - try: - from isaaclab.sim._impl.newton_manager import NewtonManager - - self._metadata = { - "physics_backend": "newton", - "num_envs": NewtonManager._num_envs if NewtonManager._num_envs is not None else 0, - "gravity_vector": NewtonManager._gravity_vector, - "clone_physics_only": NewtonManager._clone_physics_only, - } - except Exception: - self._metadata = {"physics_backend": "newton"} + self._metadata = {"physics_backend": "newton"} def update(self) -> None: - """No-op for Newton backend (state updated by Newton solver).""" + """No-op for Newton backend (stub).""" pass def get_newton_model(self) -> Any | None: - """NATIVE: Newton Model from NewtonManager.""" - try: - from isaaclab.sim._impl.newton_manager import NewtonManager - - return NewtonManager._model - except Exception: - return None + """Return Newton model handle when available.""" + return None def get_newton_state(self) -> Any | None: - """NATIVE: Newton State from NewtonManager.""" - try: - from isaaclab.sim._impl.newton_manager import NewtonManager - - return NewtonManager._state_0 - except Exception: - return None + """Return Newton state handle when available.""" + return None - def get_usd_stage(self) -> None: - """UNAVAILABLE: Newton backend doesn't provide USD (future: Newton→USD sync).""" - return + def get_usd_stage(self) -> Any | None: + """UNAVAILABLE: Newton backend doesn't provide USD stage.""" + return None def get_metadata(self) -> dict[str, Any]: return dict(self._metadata) def get_transforms(self) -> dict[str, Any] | None: - """Extract transforms from Newton state (future work).""" + """Return body transforms when available.""" return None def get_velocities(self) -> dict[str, Any] | None: - try: - from isaaclab.sim._impl.newton_manager import NewtonManager - - if NewtonManager._state_0 is None: - return None - return {"body_qd": NewtonManager._state_0.body_qd} - except Exception: - return None + """Return body velocities when available.""" + return None def get_contacts(self) -> dict[str, Any] | None: - try: - from isaaclab.sim._impl.newton_manager import NewtonManager - - if NewtonManager._contacts is None: - return None - return {"contacts": NewtonManager._contacts} - except Exception: - return None - - def get_camera_data(self) -> dict[str, Any] | None: - """UNAVAILABLE: Newton backend doesn't provide USD cameras.""" + """Return contacts when available.""" return None def get_camera_transforms(self) -> dict[str, Any] | None: - """UNAVAILABLE: Newton backend doesn't provide USD cameras.""" - return None - - def get_camera_configs(self) -> list[dict[str, Any]] | None: - """UNAVAILABLE: Newton backend doesn't provide USD camera configs.""" + """Return camera transforms when available.""" return None diff --git a/source/isaaclab/isaaclab/sim/scene_data_providers/ov_scene_data_provider.py b/source/isaaclab/isaaclab/sim/scene_data_providers/ov_scene_data_provider.py index 9e541be8f8d..1827ff42359 100644 --- a/source/isaaclab/isaaclab/sim/scene_data_providers/ov_scene_data_provider.py +++ b/source/isaaclab/isaaclab/sim/scene_data_providers/ov_scene_data_provider.py @@ -51,7 +51,6 @@ def __init__(self, visualizer_cfgs: list[Any] | None, stage, simulation_context) self._device = getattr(self._simulation_context, "device", "cuda:0") self._newton_model = None self._newton_state = None - self._camera_data_cache: dict[str, Any] | None = None self._rigid_body_paths: list[str] = [] self._articulation_paths: list[str] = [] self._set_body_q_kernel = None @@ -348,9 +347,7 @@ def _read_poses_from_best_source(self) -> tuple[Any, Any, str, Any] | None: articulation_count = self._apply_view_poses( self._articulation_view, "articulation_view", positions, orientations, covered ) - rigid_count = self._apply_view_poses( - self._rigid_body_view, "rigid_body_view", positions, orientations, covered - ) + rigid_count = self._apply_view_poses(self._rigid_body_view, "rigid_body_view", positions, orientations, covered) xform_count = self._apply_xform_poses(positions, orientations, covered, xform_mask) if not covered.all(): @@ -442,75 +439,20 @@ def get_usd_stage(self) -> Any: """Return the USD stage handle.""" return self._stage - def get_camera_data(self) -> dict[str, Any] | None: - """Return cached camera discovery data from the stage.""" - if self._stage is None: - return None - if self._camera_data_cache is None: - self._camera_data_cache = self._collect_camera_data(self._stage) - return dict(self._camera_data_cache) - def get_camera_transforms(self) -> dict[str, Any] | None: """Return per-camera, per-env transforms (positions, orientations).""" if self._stage is None: return None - camera_data = self.get_camera_data() - if not camera_data: - return None - return self._collect_camera_transforms(self._stage, camera_data) - - def get_camera_configs(self) -> list[dict[str, Any]] | None: - """Return camera intrinsics/configs for discovered cameras.""" - if self._stage is None: - return None - camera_data = self.get_camera_data() - if not camera_data: - return None - return self._collect_camera_configs(self._stage, camera_data) - - def get_metadata(self) -> dict[str, Any]: - """Return backend metadata (num_envs, gravity, etc.).""" - return dict(self._metadata) - - def get_transforms(self) -> dict[str, Any] | None: - """Return merged body transforms from available PhysX views.""" - try: - result = self._read_poses_from_best_source() - if result is None: - return None - - positions, orientations, _, xform_mask = result - orientations_xyzw = self._convert_xform_quats(orientations, xform_mask) - return {"positions": positions, "orientations": orientations_xyzw} - except Exception: - return None - - def get_velocities(self) -> dict[str, Any] | None: - """Return linear/angular velocities from available PhysX views.""" - for source, view in ( - ("articulation_view", self._articulation_view), - ("rigid_body_view", self._rigid_body_view), - ): - linear, angular = self._get_view_velocities(view) - if linear is not None and angular is not None: - return {"linear": linear, "angular": angular, "source": source} - return None - - def get_contacts(self) -> dict[str, Any] | None: - """Contacts not yet supported for OV backend.""" - return None - - @staticmethod - def _collect_camera_data(stage, env_regex: str = r"(?P/World/envs/env_)(?P\d+)(?P/.*)"): - """Collect camera prims across envs and build shared templates.""" from pxr import UsdGeom - env_pattern = re.compile(env_regex) + import isaaclab.sim as isaaclab_sim + + env_pattern = re.compile(r"(?P/World/envs/env_)(?P\d+)(?P/.*)") shared_paths: list[str] = [] instances: dict[str, list[tuple[int, str]]] = {} num_envs = -1 - stage_prims: list = [stage.GetPseudoRoot()] + stage_prims: list = [self._stage.GetPseudoRoot()] while stage_prims: prim = stage_prims.pop(0) prim_path = prim.GetPath().pathString @@ -537,17 +479,7 @@ def _collect_camera_data(stage, env_regex: str = r"(?P/World/envs/env_)(?P if child_prims := prim.GetFilteredChildren(UsdGeom.TraverseInstanceProxies()): stage_prims.extend(child_prims) - return {"shared_paths": shared_paths, "instances": instances, "num_envs": num_envs + 1} - - @staticmethod - def _collect_camera_transforms(stage, camera_data: dict[str, Any]): - """Resolve camera transforms for each shared path and env.""" - import isaaclab.sim as isaaclab_sim - - shared_paths = camera_data.get("shared_paths") or [] - instances = camera_data.get("instances") or {} - num_envs = camera_data.get("num_envs", 0) - + num_envs += 1 positions: list[list[list[float] | None]] = [] orientations: list[list[list[float] | None]] = [] @@ -557,7 +489,7 @@ def _collect_camera_transforms(stage, camera_data: dict[str, Any]): for world_id, prim_path in instances.get(template_path, []): if world_id < 0 or world_id >= num_envs: continue - prim = stage.GetPrimAtPath(prim_path) + prim = self._stage.GetPrimAtPath(prim_path) if not prim.IsValid(): continue pos, ori = isaaclab_sim.resolve_prim_pose(prim) @@ -568,34 +500,34 @@ def _collect_camera_transforms(stage, camera_data: dict[str, Any]): return {"order": shared_paths, "positions": positions, "orientations": orientations, "num_envs": num_envs} - @staticmethod - def _collect_camera_configs(stage, camera_data: dict[str, Any]) -> list[dict[str, Any]]: - """Read camera intrinsics from one instance per shared path.""" - from pxr import UsdGeom + def get_metadata(self) -> dict[str, Any]: + """Return backend metadata (num_envs, gravity, etc.).""" + return dict(self._metadata) - shared_paths = camera_data.get("shared_paths") or [] - instances = camera_data.get("instances") or {} + def get_transforms(self) -> dict[str, Any] | None: + """Return merged body transforms from available PhysX views.""" + try: + result = self._read_poses_from_best_source() + if result is None: + return None - configs: list[dict[str, Any]] = [] - for template_path in shared_paths: - prim_path = None - for _, instance_path in instances.get(template_path, []): - prim_path = instance_path - break - if not prim_path: - continue - prim = stage.GetPrimAtPath(prim_path) - if not prim.IsValid(): - continue - camera = UsdGeom.Camera(prim) - configs.append( - { - "template_path": template_path, - "prim_path": prim_path, - "focal_length": float(camera.GetFocalLengthAttr().Get()), - "horizontal_aperture": float(camera.GetHorizontalApertureAttr().Get()), - "vertical_aperture": float(camera.GetVerticalApertureAttr().Get()), - "clipping_range": tuple(camera.GetClippingRangeAttr().Get()), - } - ) - return configs + positions, orientations, _, xform_mask = result + orientations_xyzw = self._convert_xform_quats(orientations, xform_mask) + return {"positions": positions, "orientations": orientations_xyzw} + except Exception: + return None + + def get_velocities(self) -> dict[str, Any] | None: + """Return linear/angular velocities from available PhysX views.""" + for source, view in ( + ("articulation_view", self._articulation_view), + ("rigid_body_view", self._rigid_body_view), + ): + linear, angular = self._get_view_velocities(view) + if linear is not None and angular is not None: + return {"linear": linear, "angular": angular, "source": source} + return None + + def get_contacts(self) -> dict[str, Any] | None: + """Contacts not yet supported for OV backend.""" + return None diff --git a/source/isaaclab/isaaclab/sim/scene_data_providers/scene_data_provider.py b/source/isaaclab/isaaclab/sim/scene_data_providers/scene_data_provider.py index 62a260da240..0ab51f3944c 100644 --- a/source/isaaclab/isaaclab/sim/scene_data_providers/scene_data_provider.py +++ b/source/isaaclab/isaaclab/sim/scene_data_providers/scene_data_provider.py @@ -3,94 +3,58 @@ # # SPDX-License-Identifier: BSD-3-Clause -"""Scene data provider for visualizers and renderers.""" +"""Scene data provider interface for visualizers and renderers.""" from __future__ import annotations -import logging +from abc import ABC, abstractmethod from typing import Any -logger = logging.getLogger(__name__) +class SceneDataProvider(ABC): + """Backend-agnostic scene data provider interface.""" -class SceneDataProvider: - """Creates appropriate data provider based on physics backend.""" - - def __init__( - self, - backend: str, - visualizer_cfgs: list[Any] | None, - stage=None, - simulation_context=None, - ) -> None: - self._backend = backend - self._provider = None - - if backend == "newton": - from .newton_scene_data_provider import NewtonSceneDataProvider - - self._provider = NewtonSceneDataProvider(visualizer_cfgs) - elif backend == "omni": - if stage is None or simulation_context is None: - logger.warning("OV scene data provider requires stage and simulation context.") - self._provider = None - else: - from .ov_scene_data_provider import OVSceneDataProvider - - self._provider = OVSceneDataProvider(visualizer_cfgs, stage, simulation_context) - else: - logger.warning(f"Unknown physics backend '{backend}'.") - + @abstractmethod def update(self) -> None: - if self._provider is not None: - self._provider.update() + """Refresh any cached scene data.""" + raise NotImplementedError + @abstractmethod def get_newton_model(self) -> Any | None: - if self._provider is None: - return None - return self._provider.get_newton_model() + """Return Newton model handle when available.""" + raise NotImplementedError + @abstractmethod def get_newton_state(self) -> Any | None: - if self._provider is None: - return None - return self._provider.get_newton_state() + """Return Newton state handle when available.""" + raise NotImplementedError + @abstractmethod def get_usd_stage(self) -> Any | None: - if self._provider is None: - return None - return self._provider.get_usd_stage() + """Return USD stage handle when available.""" + raise NotImplementedError + @abstractmethod def get_metadata(self) -> dict[str, Any]: - if self._provider is None: - return {} - return self._provider.get_metadata() + """Return backend metadata (num_envs, gravity, etc.).""" + raise NotImplementedError + @abstractmethod def get_transforms(self) -> dict[str, Any] | None: - if self._provider is None: - return None - return self._provider.get_transforms() + """Return body transforms, if supported.""" + raise NotImplementedError + @abstractmethod def get_velocities(self) -> dict[str, Any] | None: - if self._provider is None: - return None - return self._provider.get_velocities() + """Return body velocities, if supported.""" + raise NotImplementedError + @abstractmethod def get_contacts(self) -> dict[str, Any] | None: - if self._provider is None: - return None - return self._provider.get_contacts() - - def get_camera_data(self) -> dict[str, Any] | None: - if self._provider is None: - return None - return self._provider.get_camera_data() + """Return contacts, if supported.""" + raise NotImplementedError + @abstractmethod def get_camera_transforms(self) -> dict[str, Any] | None: - if self._provider is None: - return None - return self._provider.get_camera_transforms() - - def get_camera_configs(self) -> list[dict[str, Any]] | None: - if self._provider is None: - return None - return self._provider.get_camera_configs() + """Return per-camera, per-env transforms, if supported.""" + raise NotImplementedError diff --git a/source/isaaclab/isaaclab/sim/simulation_context.py b/source/isaaclab/isaaclab/sim/simulation_context.py index eb41a1d9885..11786de4586 100644 --- a/source/isaaclab/isaaclab/sim/simulation_context.py +++ b/source/isaaclab/isaaclab/sim/simulation_context.py @@ -277,12 +277,17 @@ def _init_visualizers(self) -> None: return visualizer_cfgs = self._create_default_visualizer_configs(requested_visualizers) - self._scene_data_provider = SceneDataProvider( - backend=self.cfg.physics_backend, - visualizer_cfgs=visualizer_cfgs, - stage=self.stage, - simulation_context=self, - ) + if self.cfg.physics_backend == "newton": + from .scene_data_providers import NewtonSceneDataProvider + + self._scene_data_provider = NewtonSceneDataProvider(visualizer_cfgs) + elif self.cfg.physics_backend == "omni": + from .scene_data_providers import OVSceneDataProvider + + self._scene_data_provider = OVSceneDataProvider(visualizer_cfgs, self.stage, self) + else: + logger.warning(f"Unknown physics backend '{self.cfg.physics_backend}'. Visualizers disabled.") + return # Create and initialize each visualizer for cfg in visualizer_cfgs: diff --git a/source/isaaclab/isaaclab/visualizers/newton_visualizer.py b/source/isaaclab/isaaclab/visualizers/newton_visualizer.py index a2c50b8d640..14c0ce0b57a 100644 --- a/source/isaaclab/isaaclab/visualizers/newton_visualizer.py +++ b/source/isaaclab/isaaclab/visualizers/newton_visualizer.py @@ -9,7 +9,7 @@ import contextlib import logging -from typing import Any +from typing import TYPE_CHECKING, Any import numpy as np import warp as wp @@ -20,6 +20,9 @@ logger = logging.getLogger(__name__) +if TYPE_CHECKING: + from isaaclab.sim.scene_data_providers import SceneDataProvider + class NewtonViewerGL(ViewerGL): """Wrapper around Newton's ViewerGL with training/rendering pause controls.""" @@ -207,17 +210,16 @@ def __init__(self, cfg: NewtonVisualizerCfg): self._update_frequency = cfg.update_frequency self._scene_data_provider = None - def initialize(self, scene_data: dict[str, Any] | None = None) -> None: + def initialize(self, scene_data_provider: SceneDataProvider) -> None: if self._is_initialized: return + if scene_data_provider is None: + raise RuntimeError("Newton visualizer requires a scene_data_provider.") - if not scene_data or "scene_data_provider" not in scene_data: - raise RuntimeError("Newton visualizer requires scene_data_provider.") - - self._scene_data_provider = scene_data["scene_data_provider"] - self._model = self._scene_data_provider.get_newton_model() - self._state = self._scene_data_provider.get_newton_state() - metadata = self._scene_data_provider.get_metadata() + self._scene_data_provider = scene_data_provider + self._model = scene_data_provider.get_newton_model() + self._state = scene_data_provider.get_newton_state() + metadata = scene_data_provider.get_metadata() self._viewer = NewtonViewerGL( width=self.cfg.window_width, diff --git a/source/isaaclab/isaaclab/visualizers/ov_visualizer.py b/source/isaaclab/isaaclab/visualizers/ov_visualizer.py index d3e2c8ea822..a18b5f5344e 100644 --- a/source/isaaclab/isaaclab/visualizers/ov_visualizer.py +++ b/source/isaaclab/isaaclab/visualizers/ov_visualizer.py @@ -9,7 +9,7 @@ import asyncio import logging -from typing import Any +from typing import TYPE_CHECKING, Any from pxr import UsdGeom @@ -18,6 +18,9 @@ logger = logging.getLogger(__name__) +if TYPE_CHECKING: + from isaaclab.sim.scene_data_providers import SceneDataProvider + class OVVisualizer(Visualizer): """Omniverse visualizer using Isaac Sim viewport.""" @@ -33,13 +36,17 @@ def __init__(self, cfg: OVVisualizerCfg): self._sim_time = 0.0 self._step_counter = 0 - def initialize(self, scene_data: dict[str, Any] | None = None) -> None: + def initialize(self, scene_data_provider: SceneDataProvider) -> None: if self._is_initialized: logger.warning("[OVVisualizer] Already initialized.") return - usd_stage = scene_data["usd_stage"] - scene_data_provider = scene_data["scene_data_provider"] + if scene_data_provider is None: + raise RuntimeError("[OVVisualizer] Requires a scene_data_provider.") + self._scene_data_provider = scene_data_provider + usd_stage = scene_data_provider.get_usd_stage() + if usd_stage is None: + raise RuntimeError("[OVVisualizer] USD stage not available from scene_data_provider.") metadata = scene_data_provider.get_metadata() self._ensure_simulation_app() diff --git a/source/isaaclab/isaaclab/visualizers/rerun_visualizer.py b/source/isaaclab/isaaclab/visualizers/rerun_visualizer.py index d73e313cfdd..6833b5cdd44 100644 --- a/source/isaaclab/isaaclab/visualizers/rerun_visualizer.py +++ b/source/isaaclab/isaaclab/visualizers/rerun_visualizer.py @@ -8,7 +8,7 @@ from __future__ import annotations import logging -from typing import Any +from typing import TYPE_CHECKING, Any import rerun as rr import rerun.blueprint as rrb @@ -19,6 +19,9 @@ logger = logging.getLogger(__name__) +if TYPE_CHECKING: + from isaaclab.sim.scene_data_providers import SceneDataProvider + class NewtonViewerRerun(ViewerRerun): """Isaac Lab wrapper for Newton's ViewerRerun.""" @@ -71,18 +74,17 @@ def __init__(self, cfg: RerunVisualizerCfg): self._sim_time = 0.0 self._scene_data_provider = None - def initialize(self, scene_data: dict[str, Any] | None = None) -> None: + def initialize(self, scene_data_provider: SceneDataProvider) -> None: if self._is_initialized: logger.warning("[RerunVisualizer] Already initialized.") return + if scene_data_provider is None: + raise RuntimeError("Rerun visualizer requires a scene_data_provider.") - if not scene_data or "scene_data_provider" not in scene_data: - raise RuntimeError("Rerun visualizer requires scene_data_provider.") - - self._scene_data_provider = scene_data["scene_data_provider"] - self._model = self._scene_data_provider.get_newton_model() - self._state = self._scene_data_provider.get_newton_state() - metadata = self._scene_data_provider.get_metadata() + self._scene_data_provider = scene_data_provider + self._model = scene_data_provider.get_newton_model() + self._state = scene_data_provider.get_newton_state() + metadata = scene_data_provider.get_metadata() try: if self.cfg.record_to_rrd: diff --git a/source/isaaclab/isaaclab/visualizers/visualizer.py b/source/isaaclab/isaaclab/visualizers/visualizer.py index 554582e94b3..2106d81e4c3 100644 --- a/source/isaaclab/isaaclab/visualizers/visualizer.py +++ b/source/isaaclab/isaaclab/visualizers/visualizer.py @@ -11,6 +11,8 @@ from typing import TYPE_CHECKING, Any if TYPE_CHECKING: + from isaaclab.sim.scene_data_providers import SceneDataProvider + from .visualizer_cfg import VisualizerCfg @@ -23,12 +25,13 @@ class Visualizer(ABC): def __init__(self, cfg: VisualizerCfg): """Initialize visualizer with config.""" self.cfg = cfg + self._scene_data_provider = None self._is_initialized = False self._is_closed = False @abstractmethod - def initialize(self, scene_data: dict[str, Any] | None = None) -> None: - """Initialize visualizer with scene data (model, state, usd_stage, etc.).""" + def initialize(self, scene_data_provider: SceneDataProvider) -> None: + """Initialize visualizer resources.""" raise NotImplementedError @abstractmethod From f6bf0e231bdb7c3e25c1f607719623338ea79e6f Mon Sep 17 00:00:00 2001 From: Matthew Trepte Date: Tue, 10 Feb 2026 01:06:05 +0000 Subject: [PATCH 43/46] add initial impl for partial viz --- .../isaaclab/isaaclab/envs/direct_marl_env.py | 1 + .../isaaclab/isaaclab/envs/direct_rl_env.py | 1 + .../isaaclab/envs/manager_based_env.py | 1 + .../newton_scene_data_provider.py | 6 +- .../ov_scene_data_provider.py | 303 ++++++++++++++++-- .../isaaclab/visualizers/newton_visualizer.py | 26 +- .../isaaclab/visualizers/ov_visualizer.py | 16 +- .../isaaclab/visualizers/rerun_visualizer.py | 55 +++- .../visualizers/rerun_visualizer_cfg.py | 9 + .../isaaclab/visualizers/visualizer_cfg.py | 8 + 10 files changed, 381 insertions(+), 45 deletions(-) diff --git a/source/isaaclab/isaaclab/envs/direct_marl_env.py b/source/isaaclab/isaaclab/envs/direct_marl_env.py index 3029a22a561..ce13c8aeaa6 100644 --- a/source/isaaclab/isaaclab/envs/direct_marl_env.py +++ b/source/isaaclab/isaaclab/envs/direct_marl_env.py @@ -126,6 +126,7 @@ def __init__(self, cfg: DirectMARLEnvCfg, render_mode: str | None = None, **kwar self.scene = InteractiveScene(self.cfg.scene) self._setup_scene() attach_stage_to_usd_context() + self.sim.set_scene_info(self.scene) print("[INFO]: Scene manager: ", self.scene) # set up camera viewport controller diff --git a/source/isaaclab/isaaclab/envs/direct_rl_env.py b/source/isaaclab/isaaclab/envs/direct_rl_env.py index 17d29f7ebd8..0da092ee1ac 100644 --- a/source/isaaclab/isaaclab/envs/direct_rl_env.py +++ b/source/isaaclab/isaaclab/envs/direct_rl_env.py @@ -132,6 +132,7 @@ def __init__(self, cfg: DirectRLEnvCfg, render_mode: str | None = None, **kwargs self.scene = InteractiveScene(self.cfg.scene) self._setup_scene() attach_stage_to_usd_context() + self.sim.set_scene_info(self.scene) print("[INFO]: Scene manager: ", self.scene) # set up camera viewport controller diff --git a/source/isaaclab/isaaclab/envs/manager_based_env.py b/source/isaaclab/isaaclab/envs/manager_based_env.py index 4162b46ad77..259f69d98c3 100644 --- a/source/isaaclab/isaaclab/envs/manager_based_env.py +++ b/source/isaaclab/isaaclab/envs/manager_based_env.py @@ -139,6 +139,7 @@ def __init__(self, cfg: ManagerBasedEnvCfg): with use_stage(self.sim.stage): self.scene = InteractiveScene(self.cfg.scene) attach_stage_to_usd_context() + self.sim.set_scene_info(self.scene) print("[INFO]: Scene manager: ", self.scene) # set up camera viewport controller diff --git a/source/isaaclab/isaaclab/sim/scene_data_providers/newton_scene_data_provider.py b/source/isaaclab/isaaclab/sim/scene_data_providers/newton_scene_data_provider.py index 54564cbd2df..df871fe26e7 100644 --- a/source/isaaclab/isaaclab/sim/scene_data_providers/newton_scene_data_provider.py +++ b/source/isaaclab/isaaclab/sim/scene_data_providers/newton_scene_data_provider.py @@ -20,7 +20,7 @@ class NewtonSceneDataProvider: def __init__(self, visualizer_cfgs: list[Any] | None) -> None: self._metadata = {"physics_backend": "newton"} - def update(self) -> None: + def update(self, env_ids: list[int] | None = None) -> None: """No-op for Newton backend (stub).""" pass @@ -28,8 +28,8 @@ def get_newton_model(self) -> Any | None: """Return Newton model handle when available.""" return None - def get_newton_state(self) -> Any | None: - """Return Newton state handle when available.""" + def get_newton_state(self, env_ids: list[int] | None = None) -> Any | None: + """Return Newton state handle when available. env_ids ignored in stub.""" return None def get_usd_stage(self) -> Any | None: diff --git a/source/isaaclab/isaaclab/sim/scene_data_providers/ov_scene_data_provider.py b/source/isaaclab/isaaclab/sim/scene_data_providers/ov_scene_data_provider.py index 1827ff42359..258c6da2b1f 100644 --- a/source/isaaclab/isaaclab/sim/scene_data_providers/ov_scene_data_provider.py +++ b/source/isaaclab/isaaclab/sim/scene_data_providers/ov_scene_data_provider.py @@ -11,6 +11,8 @@ import re from typing import Any +from pxr import UsdGeom + logger = logging.getLogger(__name__) @@ -25,9 +27,44 @@ class OVSceneDataProvider: - TODO: mesh data access """ + @staticmethod + def _env_id_from_rigid_body_path(path: str) -> int | None: + """Extract env id from path like /World/envs/env_42/... Return None if no match.""" + match = re.search(r"/World/envs/env_(\d+)(/|$)", path) + return int(match.group(1)) if match else None + + def _count_envs_from_stage(self) -> int: + """Infer number of envs from USD stage by counting /World/envs/env_* prims. Returns 0 on failure.""" + if self._stage is None: + return 0 + env_pattern = re.compile(r"^/World/envs/env_(\d+)$") + count = 0 + try: + prim = self._stage.GetPrimAtPath("/World/envs") + if not prim.IsValid(): + return 0 + for child in prim.GetChildren(): + path = child.GetPath().pathString + if env_pattern.match(path): + count += 1 + return count + except Exception: + return 0 + + def get_num_envs(self) -> int: + """Return number of envs: from set value, or inferred from stage with a warning.""" + if self._num_envs is not None and self._num_envs > 0: + return self._num_envs + n = self._count_envs_from_stage() + if n <= 0: + logger.warning( + "[OVSceneDataProvider] num_envs was not set and could not be inferred from stage. " + "Call set_num_envs() after scene creation for correct behavior." + ) + return n if n > 0 else 0 + def __init__(self, visualizer_cfgs: list[Any] | None, stage, simulation_context) -> None: from isaacsim.core.simulation_manager import SimulationManager - from pxr import UsdGeom self._stage = stage self._simulation_context = simulation_context @@ -37,40 +74,55 @@ def __init__(self, visualizer_cfgs: list[Any] | None, stage, simulation_context) self._xform_views: dict[str, Any] = {} self._view_body_index_map: dict[str, list[int]] = {} + # Scene info: set via set_num_envs/set_env_origins after creation (by sim, from env). + self._num_envs: int | None = None + self._env_origins: Any = None + viz_types = {getattr(cfg, "visualizer_type", None) for cfg in (visualizer_cfgs or [])} - # Explicit mode flag for Newton synchronization self._needs_newton_sync = bool({"newton", "rerun"} & viz_types) + # Metadata: only fixed backend info. num_envs/env_origins come from get_num_envs()/self._env_origins. self._metadata = { "physics_backend": "omni", - "num_envs": self._get_num_envs(), "gravity_vector": tuple(self._simulation_context.cfg.gravity), "clone_physics_only": False, } + self._up_axis = UsdGeom.GetStageUpAxis(self._stage) + self._num_envs_at_last_newton_build: int | None = None # for _refresh_newton_model_if_needed self._device = getattr(self._simulation_context, "device", "cuda:0") self._newton_model = None self._newton_state = None + self._filtered_newton_model = None + self._filtered_newton_state = None + self._filtered_env_ids_key: tuple[int, ...] | None = None + self._filtered_body_indices: list[int] = [] self._rigid_body_paths: list[str] = [] self._articulation_paths: list[str] = [] self._set_body_q_kernel = None - self._up_axis = UsdGeom.GetStageUpAxis(self._stage) + # env_id -> list of body indices (in Newton body_key order) + self._env_id_to_body_indices: dict[int, list[int]] = {} + # flat list of body indices per env_id order for subset sync + self._body_indices_for_env_ids: list[int] = [] # Initialize Newton pipeline only if needed for visualization if self._needs_newton_sync: self._build_newton_model_from_usd() + self._build_env_id_to_body_indices() self._setup_rigid_body_view() self._setup_articulation_view() else: logger.info("[OVSceneDataProvider] OV visualizer only - skipping Newton model build") - def _get_num_envs(self) -> int: - """Read num_envs from settings; returns 0 if unset/unavailable.""" - import carb + def set_num_envs(self, num_envs: int) -> None: + """Set number of environments. Called after scene creation (by sim, from env).""" + self._num_envs = num_envs + if self._needs_newton_sync and self._newton_model is not None: + self._refresh_newton_model_if_needed() - carb_settings_iface = carb.settings.get_settings() - num_envs = carb_settings_iface.get("/isaaclab/scene/num_envs") - return int(num_envs) if num_envs else 0 + def set_env_origins(self, env_origins: Any) -> None: + """Set env origins tensor/array (num_envs, 3). Called after scene creation when available.""" + self._env_origins = env_origins @staticmethod def _wildcard_env_paths(paths: list[str]) -> list[str]: @@ -82,12 +134,12 @@ def _wildcard_env_paths(paths: list[str]) -> list[str]: def _refresh_newton_model_if_needed(self) -> None: """Rebuild Newton model/state and PhysX views if env count changes.""" - num_envs = self._get_num_envs() + num_envs = self.get_num_envs() if num_envs <= 0: return needs_rebuild = self._newton_model is None or self._newton_state is None - needs_rebuild = needs_rebuild or (self._metadata.get("num_envs", 0) != num_envs) + needs_rebuild = needs_rebuild or (self._num_envs_at_last_newton_build != num_envs) if needs_rebuild: self._build_newton_model_from_usd() self._setup_rigid_body_view() @@ -109,6 +161,13 @@ def _build_newton_model_from_usd(self) -> None: self._xform_views.clear() self._view_body_index_map = {} + self._env_id_to_body_indices = {} + self._num_envs_at_last_newton_build = self.get_num_envs() + # Invalidate any filtered model when full model changes. + self._filtered_newton_model = None + self._filtered_newton_state = None + self._filtered_env_ids_key = None + self._filtered_body_indices = [] except ModuleNotFoundError as exc: logger.error( "[SceneDataProvider] Newton module not available. " @@ -121,6 +180,57 @@ def _build_newton_model_from_usd(self) -> None: self._newton_state = None self._rigid_body_paths = [] self._articulation_paths = [] + self._num_envs_at_last_newton_build = None + + def _build_filtered_newton_model(self, env_ids: list[int]) -> None: + """Build Newton model/state for a subset of envs.""" + try: + from newton import ModelBuilder + + builder = ModelBuilder(up_axis=self._up_axis) + builder.add_usd(self._stage, ignore_paths=[r"/World/envs/.*"]) + for env_id in env_ids: + builder.add_usd(self._stage, root_path=f"/World/envs/env_{env_id}") + self._filtered_newton_model = builder.finalize(device=self._device) + self._filtered_newton_state = self._filtered_newton_model.state() + + full_index_by_path = {path: i for i, path in enumerate(self._rigid_body_paths)} + filtered_paths = list(self._filtered_newton_model.body_key) + self._filtered_body_indices = [] + missing = [] + for path in filtered_paths: + idx = full_index_by_path.get(path) + if idx is None: + missing.append(path) + else: + self._filtered_body_indices.append(idx) + if missing: + logger.warning( + "[OVSceneDataProvider] Filtered model contains %d bodies not in full model.", + len(missing), + ) + except ModuleNotFoundError as exc: + logger.error( + "[SceneDataProvider] Newton module not available. " + "Install the Newton backend to use newton/rerun visualizers." + ) + logger.debug(f"[SceneDataProvider] Newton import error: {exc}") + self._filtered_newton_model = None + self._filtered_newton_state = None + self._filtered_body_indices = [] + except Exception as exc: + logger.error(f"[SceneDataProvider] Failed to build filtered Newton model from USD: {exc}") + self._filtered_newton_model = None + self._filtered_newton_state = None + self._filtered_body_indices = [] + + def _build_env_id_to_body_indices(self) -> None: + """Build mapping env_id -> list of body indices from rigid_body_paths.""" + self._env_id_to_body_indices = {} + for body_idx, path in enumerate(self._rigid_body_paths): + eid = self._env_id_from_rigid_body_path(path) + if eid is not None: + self._env_id_to_body_indices.setdefault(eid, []).append(body_idx) def _setup_rigid_body_view(self) -> None: """Create PhysX RigidBodyView from Newton's body paths. @@ -393,8 +503,37 @@ def _set_body_q( logger.warning(f"[SceneDataProvider] Warp unavailable for Newton state sync: {exc}") return None - def update(self) -> None: - """Sync PhysX transforms to Newton state for visualization.""" + def _get_set_body_q_subset_kernel(self): + """Kernel that writes only body_q at given indices.""" + kernel = getattr(self, "_set_body_q_subset_kernel", None) + if kernel is not None: + return kernel + try: + import warp as wp + + @wp.kernel(enable_backward=False) + def _set_body_q_subset( + positions: wp.array(dtype=wp.vec3), + orientations: wp.array(dtype=wp.quatf), + body_indices: wp.array(dtype=wp.int32), + body_q: wp.array(dtype=wp.transformf), + ): + i = wp.tid() + bi = body_indices[i] + body_q[bi] = wp.transformf(positions[i], orientations[i]) + + self._set_body_q_subset_kernel = _set_body_q_subset + return self._set_body_q_subset_kernel + except Exception as exc: + logger.debug(f"Warp subset kernel: {exc}") + return None + + def update(self, env_ids: list[int] | None = None) -> None: + """Sync PhysX transforms to Newton state for visualization. + + When env_ids is not None, only body indices belonging to those envs are written + (partial sync). When None, all bodies are synced. + """ if not self._needs_newton_sync or self._newton_state is None: return @@ -413,17 +552,39 @@ def update(self) -> None: positions_wp = wp.from_torch(positions.reshape(-1, 3), dtype=wp.vec3) orientations_wp = wp.from_torch(orientations_xyzw, dtype=wp.quatf) - set_body_q = self._get_set_body_q_kernel() - if set_body_q is None or positions_wp.shape[0] != self._newton_state.body_q.shape[0]: - return - - wp.launch( - set_body_q, - dim=positions_wp.shape[0], - inputs=[positions_wp, orientations_wp, self._newton_state.body_q], - device=self._device, - ) - + if env_ids is None or not env_ids or not self._env_id_to_body_indices: + set_body_q = self._get_set_body_q_kernel() + if set_body_q is None or positions_wp.shape[0] != self._newton_state.body_q.shape[0]: + return + wp.launch( + set_body_q, + dim=positions_wp.shape[0], + inputs=[positions_wp, orientations_wp, self._newton_state.body_q], + device=self._device, + ) + else: + body_indices = [] + for eid in env_ids: + body_indices.extend(self._env_id_to_body_indices.get(eid, [])) + if not body_indices: + return + subset_kernel = self._get_set_body_q_subset_kernel() + if subset_kernel is None: + return + import torch + + indices_t = torch.tensor(body_indices, dtype=torch.int32, device=self._device) + pos_subset = positions.reshape(-1, 3)[body_indices] + ori_subset = orientations_xyzw[body_indices] + indices_wp = wp.from_torch(indices_t, dtype=wp.int32) + pos_wp = wp.from_torch(pos_subset.contiguous(), dtype=wp.vec3) + ori_wp = wp.from_torch(ori_subset.contiguous(), dtype=wp.quatf) + wp.launch( + subset_kernel, + dim=len(body_indices), + inputs=[pos_wp, ori_wp, indices_wp, self._newton_state.body_q], + device=self._device, + ) except Exception as exc: logger.debug(f"Failed to sync transforms to Newton: {exc}") @@ -431,9 +592,83 @@ def get_newton_model(self) -> Any | None: """Return Newton model when sync is enabled.""" return self._newton_model if self._needs_newton_sync else None - def get_newton_state(self) -> Any | None: - """Return Newton state when sync is enabled.""" - return self._newton_state if self._needs_newton_sync else None + def get_newton_model_for_env_ids(self, env_ids: list[int] | None) -> Any | None: + """Return Newton model for a subset of envs if requested.""" + if not self._needs_newton_sync: + return None + if env_ids is None: + return self._newton_model + env_ids_key = tuple(sorted(env_ids)) + if self._filtered_newton_model is None or self._filtered_env_ids_key != env_ids_key: + self._filtered_env_ids_key = env_ids_key + self._build_filtered_newton_model(list(env_ids_key)) + return self._filtered_newton_model + + def get_newton_state(self, env_ids: list[int] | None = None) -> Any | None: + """Return Newton state when sync is enabled. + + If env_ids is None, returns the full state. If env_ids is provided, returns a + state-like object whose body_q contains only the bodies for those envs (same order + as in the full model, for use with e.g. max_worlds=len(env_ids)). + """ + if not self._needs_newton_sync or self._newton_state is None: + return None + if env_ids is None: + return self._newton_state + if not self._env_id_to_body_indices: + return self._create_empty_subset_state() + env_ids_key = tuple(sorted(env_ids)) + if self._filtered_newton_model is not None and self._filtered_env_ids_key == env_ids_key: + if not self._filtered_body_indices: + return self._create_empty_subset_state() + try: + import warp as wp + + body_q_t = wp.to_torch(self._newton_state.body_q) + subset = body_q_t[self._filtered_body_indices].clone() + self._filtered_newton_state.body_q = wp.from_torch(subset, dtype=wp.transformf) + return self._filtered_newton_state + except Exception: + return self._newton_state + body_indices = [] + for eid in env_ids: + body_indices.extend(self._env_id_to_body_indices.get(eid, [])) + if not body_indices: + return self._create_empty_subset_state() + + body_q = self._newton_state.body_q + try: + import warp as wp + + body_q_t = wp.to_torch(body_q) + body_q_subset = body_q_t[body_indices].clone() + except Exception: + return self._newton_state + return self._create_subset_state(body_q_subset) + + def _create_empty_subset_state(self): + """Return a minimal state-like object with empty body_q.""" + if self._newton_state is None: + return None + try: + import warp as wp + + body_q_t = wp.to_torch(self._newton_state.body_q) + empty = body_q_t[:0].clone() + return self._create_subset_state(empty) + except Exception: + return self._newton_state + + @staticmethod + def _create_subset_state(body_q_subset): + """Return a minimal state-like object for subset rendering.""" + + class _SubsetState: + pass + + s = _SubsetState() + s.body_q = body_q_subset + return s def get_usd_stage(self) -> Any: """Return the USD stage handle.""" @@ -501,8 +736,16 @@ def get_camera_transforms(self) -> dict[str, Any] | None: return {"order": shared_paths, "positions": positions, "orientations": orientations, "num_envs": num_envs} def get_metadata(self) -> dict[str, Any]: - """Return backend metadata (num_envs, gravity, etc.).""" - return dict(self._metadata) + """Return backend metadata (num_envs, gravity, etc.). num_envs is resolved dynamically when not set.""" + out = dict(self._metadata) + out["num_envs"] = self.get_num_envs() + if self._env_origins is not None: + out["env_origins"] = self._env_origins + return out + + def get_env_origins(self) -> Any | None: + """Return env origins (num_envs, 3) when set by the scene. None if not set.""" + return self._env_origins def get_transforms(self) -> dict[str, Any] | None: """Return merged body transforms from available PhysX views.""" diff --git a/source/isaaclab/isaaclab/visualizers/newton_visualizer.py b/source/isaaclab/isaaclab/visualizers/newton_visualizer.py index 14c0ce0b57a..547dbd6f953 100644 --- a/source/isaaclab/isaaclab/visualizers/newton_visualizer.py +++ b/source/isaaclab/isaaclab/visualizers/newton_visualizer.py @@ -27,7 +27,13 @@ class NewtonViewerGL(ViewerGL): """Wrapper around Newton's ViewerGL with training/rendering pause controls.""" - def __init__(self, *args, metadata: dict | None = None, update_frequency: int = 1, **kwargs): + def __init__( + self, + *args, + metadata: dict | None = None, + update_frequency: int = 1, + **kwargs, + ): super().__init__(*args, **kwargs) self._paused_training = False self._paused_rendering = False @@ -217,9 +223,17 @@ def initialize(self, scene_data_provider: SceneDataProvider) -> None: raise RuntimeError("Newton visualizer requires a scene_data_provider.") self._scene_data_provider = scene_data_provider - self._model = scene_data_provider.get_newton_model() - self._state = scene_data_provider.get_newton_state() metadata = scene_data_provider.get_metadata() + self._env_ids = self._compute_visualized_env_ids() + if self._env_ids: + get_filtered_model = getattr(scene_data_provider, "get_newton_model_for_env_ids", None) + if callable(get_filtered_model): + self._model = get_filtered_model(self._env_ids) + else: + self._model = scene_data_provider.get_newton_model() + else: + self._model = scene_data_provider.get_newton_model() + self._state = scene_data_provider.get_newton_state(self._env_ids) self._viewer = NewtonViewerGL( width=self.cfg.window_width, @@ -268,7 +282,7 @@ def step(self, dt: float, state: Any | None = None) -> None: self._sim_time += dt self._step_counter += 1 - self._state = self._scene_data_provider.get_newton_state() + self._state = self._scene_data_provider.get_newton_state(self._env_ids) contacts = None if self._viewer.show_contacts: @@ -286,6 +300,10 @@ def step(self, dt: float, state: Any | None = None) -> None: if not self._viewer.is_paused(): self._viewer.begin_frame(self._sim_time) if self._state is not None: + body_q = getattr(self._state, "body_q", None) + if hasattr(body_q, "shape") and body_q.shape[0] == 0: + self._viewer.end_frame() + return self._viewer.log_state(self._state) if contacts is not None and hasattr(self._viewer, "log_contacts"): try: diff --git a/source/isaaclab/isaaclab/visualizers/ov_visualizer.py b/source/isaaclab/isaaclab/visualizers/ov_visualizer.py index a18b5f5344e..f7ef5a43b16 100644 --- a/source/isaaclab/isaaclab/visualizers/ov_visualizer.py +++ b/source/isaaclab/isaaclab/visualizers/ov_visualizer.py @@ -52,9 +52,16 @@ def initialize(self, scene_data_provider: SceneDataProvider) -> None: self._ensure_simulation_app() self._setup_viewport(usd_stage, metadata) + self._env_ids = self._compute_visualized_env_ids() + if self._env_ids: + logger.warning("[OVVisualizer] env_ids filtering is not supported yet. All environments will be shown.") + self._env_ids = None num_envs = metadata.get("num_envs", 0) physics_backend = metadata.get("physics_backend", "unknown") - logger.info(f"[OVVisualizer] Initialized ({num_envs} envs, {physics_backend} physics)") + logger.info( + f"[OVVisualizer] Initialized ({num_envs} envs, {physics_backend} physics)" + + (f", showing {len(self._env_ids)} envs" if self._env_ids is not None else "") + ) self._is_initialized = True @@ -122,13 +129,14 @@ def _setup_viewport(self, usd_stage, metadata: dict) -> None: from omni.ui import DockPosition if self.cfg.create_viewport and self.cfg.viewport_name: + dock_position_name = self.cfg.dock_position.upper() dock_position_map = { "LEFT": DockPosition.LEFT, "RIGHT": DockPosition.RIGHT, "BOTTOM": DockPosition.BOTTOM, "SAME": DockPosition.SAME, } - dock_pos = dock_position_map.get(self.cfg.dock_position.upper(), DockPosition.SAME) + dock_pos = dock_position_map.get(dock_position_name, DockPosition.SAME) self._viewport_window = vp_utils.create_viewport_window( name=self.cfg.viewport_name, @@ -196,12 +204,12 @@ def _create_and_assign_camera(self, usd_stage) -> None: self._viewport_api.set_active_camera(camera_path) def _set_viewport_camera(self, position: tuple[float, float, float], target: tuple[float, float, float]) -> None: - import isaacsim.core.utils.viewports as vp_utils + import isaacsim.core.utils.viewports as isaacsim_viewports camera_path = self._viewport_api.get_active_camera() if not camera_path: camera_path = "/OmniverseKit_Persp" - vp_utils.set_camera_view( + isaacsim_viewports.set_camera_view( eye=list(position), target=list(target), camera_prim_path=camera_path, viewport_api=self._viewport_api ) diff --git a/source/isaaclab/isaaclab/visualizers/rerun_visualizer.py b/source/isaaclab/isaaclab/visualizers/rerun_visualizer.py index 6833b5cdd44..25d84db9424 100644 --- a/source/isaaclab/isaaclab/visualizers/rerun_visualizer.py +++ b/source/isaaclab/isaaclab/visualizers/rerun_visualizer.py @@ -7,6 +7,7 @@ from __future__ import annotations +import contextlib import logging from typing import TYPE_CHECKING, Any @@ -29,7 +30,9 @@ class NewtonViewerRerun(ViewerRerun): def __init__( self, app_id: str | None = None, + address: str | None = None, web_port: int | None = None, + grpc_port: int | None = None, keep_historical_data: bool = False, keep_scalar_history: bool = True, record_to_rrd: str | None = None, @@ -37,7 +40,9 @@ def __init__( ): super().__init__( app_id=app_id, + address=address, web_port=web_port, + grpc_port=grpc_port or 9876, serve_web_viewer=True, keep_historical_data=keep_historical_data, keep_scalar_history=keep_scalar_history, @@ -73,6 +78,7 @@ def __init__(self, cfg: RerunVisualizerCfg): self._is_initialized = False self._sim_time = 0.0 self._scene_data_provider = None + self._rerun_server_process = None def initialize(self, scene_data_provider: SceneDataProvider) -> None: if self._is_initialized: @@ -82,17 +88,51 @@ def initialize(self, scene_data_provider: SceneDataProvider) -> None: raise RuntimeError("Rerun visualizer requires a scene_data_provider.") self._scene_data_provider = scene_data_provider - self._model = scene_data_provider.get_newton_model() - self._state = scene_data_provider.get_newton_state() metadata = scene_data_provider.get_metadata() + self._env_ids = self._compute_visualized_env_ids() + if self._env_ids: + get_filtered_model = getattr(scene_data_provider, "get_newton_model_for_env_ids", None) + if callable(get_filtered_model): + self._model = get_filtered_model(self._env_ids) + else: + self._model = scene_data_provider.get_newton_model() + else: + self._model = scene_data_provider.get_newton_model() + self._state = scene_data_provider.get_newton_state(self._env_ids) try: if self.cfg.record_to_rrd: logger.info(f"[RerunVisualizer] Recording enabled to: {self.cfg.record_to_rrd}") + address = None + if self.cfg.bind_address: + import shutil + import subprocess + + rerun_bin = shutil.which("rerun") + if rerun_bin is None: + logger.warning("[RerunVisualizer] 'rerun' binary not found in PATH. Skipping external bind.") + else: + cmd = [ + rerun_bin, + "--serve-web", + "--bind", + self.cfg.bind_address, + "--port", + str(self.cfg.grpc_port), + "--web-viewer-port", + str(self.cfg.web_port), + ] + if self.cfg.open_browser: + cmd.append("--web-viewer") + self._rerun_server_process = subprocess.Popen(cmd) + address = f"rerun+http://127.0.0.1:{self.cfg.grpc_port}/proxy" + self._viewer = NewtonViewerRerun( app_id=self.cfg.app_id, + address=address, web_port=self.cfg.web_port, + grpc_port=self.cfg.grpc_port, keep_historical_data=self.cfg.keep_historical_data, keep_scalar_history=self.cfg.keep_scalar_history, record_to_rrd=self.cfg.record_to_rrd, @@ -125,7 +165,10 @@ def initialize(self, scene_data_provider: SceneDataProvider) -> None: num_envs = metadata.get("num_envs", 0) physics_backend = metadata.get("physics_backend", "unknown") - logger.info(f"[RerunVisualizer] Initialized with {num_envs} environments (physics: {physics_backend})") + msg = f"[RerunVisualizer] Initialized with {num_envs} environments (physics: {physics_backend})" + if self._env_ids is not None: + msg += f", showing {len(self._env_ids)} envs" + logger.info(msg) self._is_initialized = True except Exception as exc: @@ -133,7 +176,7 @@ def initialize(self, scene_data_provider: SceneDataProvider) -> None: raise def step(self, dt: float, state: Any | None = None) -> None: - self._state = self._scene_data_provider.get_newton_state() + self._state = self._scene_data_provider.get_newton_state(self._env_ids) self._sim_time += dt self._viewer.begin_frame(self._sim_time) @@ -162,6 +205,10 @@ def close(self) -> None: self._viewer = None self._is_initialized = False + if self._rerun_server_process is not None: + with contextlib.suppress(Exception): + self._rerun_server_process.terminate() + self._rerun_server_process = None def is_running(self) -> bool: if self._viewer is None: diff --git a/source/isaaclab/isaaclab/visualizers/rerun_visualizer_cfg.py b/source/isaaclab/isaaclab/visualizers/rerun_visualizer_cfg.py index 8b1e32d7ded..7c9fbb6a909 100644 --- a/source/isaaclab/isaaclab/visualizers/rerun_visualizer_cfg.py +++ b/source/isaaclab/isaaclab/visualizers/rerun_visualizer_cfg.py @@ -25,6 +25,15 @@ class RerunVisualizerCfg(VisualizerCfg): web_port: int = 9090 """Port of the local rerun web viewer which is launched in the browser.""" + grpc_port: int = 9876 + """Port of the rerun gRPC server (used when serving web viewer externally).""" + + bind_address: str | None = "0.0.0.0" + """If set, start a rerun server bound to this address (e.g. '0.0.0.0') and connect to it.""" + + open_browser: bool = True + """Whether to auto-open a browser when serving the rerun web viewer.""" + keep_historical_data: bool = False """Keep transform history for time scrubbing (False = constant memory for training).""" diff --git a/source/isaaclab/isaaclab/visualizers/visualizer_cfg.py b/source/isaaclab/isaaclab/visualizers/visualizer_cfg.py index 1b3e6777439..a2558c45882 100644 --- a/source/isaaclab/isaaclab/visualizers/visualizer_cfg.py +++ b/source/isaaclab/isaaclab/visualizers/visualizer_cfg.py @@ -47,6 +47,14 @@ class VisualizerCfg: camera_target: tuple[float, float, float] = (0.0, 0.0, 0.0) """Initial camera target/look-at point (x, y, z) in world coordinates.""" + env_ids: list[int] | None = [0] + """If set, only these env indices are shown; all other envs are filtered from visualization. + + This improves performance, particularly for large-scale training, by limiting which + environments are sent to visualizers. Backend support varies (e.g., OV ignores + this for now). + """ + def get_visualizer_type(self) -> str | None: """Get the visualizer type identifier. From b1f04ee4fbf9a311ed2eed2dd1a6640ba2d2f3ba Mon Sep 17 00:00:00 2001 From: Matthew Trepte Date: Tue, 10 Feb 2026 03:21:15 +0000 Subject: [PATCH 44/46] wip on fixing merge --- .../isaaclab/isaaclab/envs/direct_marl_env.py | 7 +- .../isaaclab/isaaclab/envs/direct_rl_env.py | 7 +- .../isaaclab/envs/manager_based_env.py | 7 +- .../isaaclab/envs/manager_based_rl_env.py | 7 +- .../isaaclab/scene/interactive_scene.py | 5 +- .../scene_data_provider.py | 2 +- .../isaaclab/sim/simulation_context.py | 95 +++++++--- .../spawners/materials/visual_materials.py | 173 ------------------ .../isaaclab/visualizers/rerun_visualizer.py | 3 + .../isaaclab/visualizers/visualizer.py | 23 +++ .../isaaclab/visualizers/visualizer_cfg.py | 2 +- 11 files changed, 123 insertions(+), 208 deletions(-) diff --git a/source/isaaclab/isaaclab/envs/direct_marl_env.py b/source/isaaclab/isaaclab/envs/direct_marl_env.py index ce13c8aeaa6..656ef47dbd9 100644 --- a/source/isaaclab/isaaclab/envs/direct_marl_env.py +++ b/source/isaaclab/isaaclab/envs/direct_marl_env.py @@ -389,8 +389,11 @@ def step(self, actions: dict[AgentID, ActionType]) -> EnvStepReturn: # render between steps only if the GUI or an RTX sensor needs it # note: we assume the render interval to be the shortest accepted rendering interval. # If a camera needs rendering at a faster frequency, this will lead to unexpected behavior. - if self._sim_step_counter % self.cfg.sim.render_interval == 0 and is_rendering: - self.sim.render() + if self._sim_step_counter % self.cfg.sim.render_interval == 0: + if is_rendering: + self.sim.render() + else: + self.sim.update_visualizers(self.sim.get_rendering_dt()) # update buffers at sim dt self.scene.update(dt=self.physics_dt) diff --git a/source/isaaclab/isaaclab/envs/direct_rl_env.py b/source/isaaclab/isaaclab/envs/direct_rl_env.py index 0da092ee1ac..77ea060c4e3 100644 --- a/source/isaaclab/isaaclab/envs/direct_rl_env.py +++ b/source/isaaclab/isaaclab/envs/direct_rl_env.py @@ -379,8 +379,11 @@ def step(self, action: torch.Tensor) -> VecEnvStepReturn: # render between steps only if the GUI or an RTX sensor needs it # note: we assume the render interval to be the shortest accepted rendering interval. # If a camera needs rendering at a faster frequency, this will lead to unexpected behavior. - if self._sim_step_counter % self.cfg.sim.render_interval == 0 and is_rendering: - self.sim.render() + if self._sim_step_counter % self.cfg.sim.render_interval == 0: + if is_rendering: + self.sim.render() + else: + self.sim.update_visualizers(self.sim.get_rendering_dt()) # update buffers at sim dt self.scene.update(dt=self.physics_dt) diff --git a/source/isaaclab/isaaclab/envs/manager_based_env.py b/source/isaaclab/isaaclab/envs/manager_based_env.py index 259f69d98c3..0df3e8d0e7b 100644 --- a/source/isaaclab/isaaclab/envs/manager_based_env.py +++ b/source/isaaclab/isaaclab/envs/manager_based_env.py @@ -486,8 +486,11 @@ def step(self, action: torch.Tensor) -> tuple[VecEnvObs, dict]: # render between steps only if the GUI or an RTX sensor needs it # note: we assume the render interval to be the shortest accepted rendering interval. # If a camera needs rendering at a faster frequency, this will lead to unexpected behavior. - if self._sim_step_counter % self.cfg.sim.render_interval == 0 and is_rendering: - self.sim.render() + if self._sim_step_counter % self.cfg.sim.render_interval == 0: + if is_rendering: + self.sim.render() + else: + self.sim.update_visualizers(self.sim.get_rendering_dt()) # update buffers at sim dt self.scene.update(dt=self.physics_dt) diff --git a/source/isaaclab/isaaclab/envs/manager_based_rl_env.py b/source/isaaclab/isaaclab/envs/manager_based_rl_env.py index eb80c75d80b..29b0c79e0be 100644 --- a/source/isaaclab/isaaclab/envs/manager_based_rl_env.py +++ b/source/isaaclab/isaaclab/envs/manager_based_rl_env.py @@ -191,8 +191,11 @@ def step(self, action: torch.Tensor) -> VecEnvStepReturn: # render between steps only if the GUI or an RTX sensor needs it # note: we assume the render interval to be the shortest accepted rendering interval. # If a camera needs rendering at a faster frequency, this will lead to unexpected behavior. - if self._sim_step_counter % self.cfg.sim.render_interval == 0 and is_rendering: - self.sim.render() + if self._sim_step_counter % self.cfg.sim.render_interval == 0: + if is_rendering: + self.sim.render() + else: + self.sim.update_visualizers(self.sim.get_rendering_dt()) # update buffers at sim dt self.scene.update(dt=self.physics_dt) diff --git a/source/isaaclab/isaaclab/scene/interactive_scene.py b/source/isaaclab/isaaclab/scene/interactive_scene.py index f7229c9fce9..1f7695be003 100644 --- a/source/isaaclab/isaaclab/scene/interactive_scene.py +++ b/source/isaaclab/isaaclab/scene/interactive_scene.py @@ -5,6 +5,7 @@ from __future__ import annotations +import contextlib import logging from collections.abc import Sequence from typing import Any @@ -140,10 +141,8 @@ def __init__(self, cfg: InteractiveSceneCfg): self.stage = get_current_stage() self.stage_id = get_current_stage_id() # publish num_envs for consumers outside the scene - try: + with contextlib.suppress(Exception): self.sim.set_setting("/isaaclab/scene/num_envs", int(self.cfg.num_envs)) - except Exception: - pass # physics scene path self._physics_scene_path = None # prepare cloner for environment replication diff --git a/source/isaaclab/isaaclab/sim/scene_data_providers/scene_data_provider.py b/source/isaaclab/isaaclab/sim/scene_data_providers/scene_data_provider.py index 0ab51f3944c..8475d5c6fa8 100644 --- a/source/isaaclab/isaaclab/sim/scene_data_providers/scene_data_provider.py +++ b/source/isaaclab/isaaclab/sim/scene_data_providers/scene_data_provider.py @@ -15,7 +15,7 @@ class SceneDataProvider(ABC): """Backend-agnostic scene data provider interface.""" @abstractmethod - def update(self) -> None: + def update(self, env_ids: list[int] | None = None) -> None: """Refresh any cached scene data.""" raise NotImplementedError diff --git a/source/isaaclab/isaaclab/sim/simulation_context.py b/source/isaaclab/isaaclab/sim/simulation_context.py index 11786de4586..e6da2ad33e3 100644 --- a/source/isaaclab/isaaclab/sim/simulation_context.py +++ b/source/isaaclab/isaaclab/sim/simulation_context.py @@ -123,9 +123,12 @@ def __init__(self, cfg: SimulationCfg | None = None): self.physics_manager: type[PhysicsManager] = self._physics.class_type self.physics_manager.initialize(self) - # Initialize visualizers and scene data provider + # Initialize visualizer state (created after scene info is available) self._scene_data_provider: SceneDataProvider | None = None - self._init_visualizers() + self._visualizers: list[Visualizer] = [] + self._visualizer_step_counter = 0 + self._num_envs: int | None = None + self._env_origins: Any = None # Cache commonly-used settings (these don't change during runtime) self._has_gui = bool(self.get_setting("/isaaclab/has_gui")) @@ -225,6 +228,9 @@ def set_scene_info(self, scene: Any) -> None: if callable(set_env_origins): set_env_origins(env_origins) + if not self._visualizers: + self.initialize_visualizers() + def _create_default_visualizer_configs(self, requested_visualizers: list[str]) -> list: """Create default visualizer configs for requested types.""" default_configs = [] @@ -258,6 +264,8 @@ def resolve_visualizer_types(self) -> list[str]: def initialize_visualizers(self) -> None: """Initialize visualizers from SimulationCfg.visualizer_cfgs.""" + if self._visualizers: + return self._init_visualizers() def _init_visualizers(self) -> None: @@ -267,9 +275,9 @@ def _init_visualizers(self) -> None: visualizer_cfgs: list = [] if self.cfg.visualizer_cfgs is not None: - visualizer_cfgs = self.cfg.visualizer_cfgs if isinstance(self.cfg.visualizer_cfgs, list) else [ - self.cfg.visualizer_cfgs - ] + visualizer_cfgs = ( + self.cfg.visualizer_cfgs if isinstance(self.cfg.visualizer_cfgs, list) else [self.cfg.visualizer_cfgs] + ) if len(visualizer_cfgs) == 0: requested_visualizers = self.resolve_visualizer_types() @@ -289,21 +297,27 @@ def _init_visualizers(self) -> None: logger.warning(f"Unknown physics backend '{self.cfg.physics_backend}'. Visualizers disabled.") return + if self._num_envs is not None and self._scene_data_provider is not None: + set_num_envs = getattr(self._scene_data_provider, "set_num_envs", None) + if callable(set_num_envs): + set_num_envs(self._num_envs) + if self._env_origins is not None and self._scene_data_provider is not None: + set_env_origins = getattr(self._scene_data_provider, "set_env_origins", None) + if callable(set_env_origins): + set_env_origins(self._env_origins) + + if self._num_envs is None or self._num_envs <= 0: + logger.warning( + "[SimulationContext] Visualizers initialized before scene info is set; " + "num_envs/env_origins are unavailable. Call set_scene_info(...) before " + "initialize_visualizers for correct partial visualization." + ) + # Create and initialize each visualizer for cfg in visualizer_cfgs: try: visualizer = cfg.create_visualizer() - scene_data: dict[str, Any] = {"scene_data_provider": self._scene_data_provider} - - # OV visualizer gets USD stage and simulation context. - if cfg.visualizer_type == "omniverse": - if self._scene_data_provider: - scene_data["usd_stage"] = self._scene_data_provider.get_usd_stage() - else: - scene_data["usd_stage"] = self.stage - scene_data["simulation_context"] = self - - visualizer.initialize(scene_data) + visualizer.initialize(self._scene_data_provider) self._visualizers.append(visualizer) logger.info(f"Initialized visualizer: {type(visualizer).__name__} (type: {cfg.visualizer_type})") except Exception as exc: @@ -353,17 +367,54 @@ def step(self, render: bool = True) -> None: def render(self, mode: int | None = None) -> None: """Render the scene via all active visualizers.""" - self.physics_manager.forward() - if self._scene_data_provider: - self._scene_data_provider.update() - for viz in self._visualizers: - if not viz.is_rendering_paused() and viz.is_running(): - viz.step(self.get_rendering_dt(), state=None) + self.update_visualizers(self.get_rendering_dt()) # Call render callbacks if hasattr(self, "_render_callbacks"): for callback in self._render_callbacks.values(): callback(None) # Pass None as event data + def update_visualizers(self, dt: float) -> None: + """Update visualizers without triggering renderer/GUI.""" + if not self._visualizers: + return + + self.physics_manager.forward() + self._visualizer_step_counter += 1 + if self._scene_data_provider: + env_ids_union: list[int] = [] + for viz in self._visualizers: + ids = getattr(viz, "get_visualized_env_ids", lambda: None)() + if ids is not None: + env_ids_union.extend(ids) + env_ids = list(dict.fromkeys(env_ids_union)) if env_ids_union else None + self._scene_data_provider.update(env_ids) + + visualizers_to_remove = [] + for viz in self._visualizers: + try: + if viz.is_rendering_paused(): + continue + if getattr(viz, "is_closed", False): + visualizers_to_remove.append(viz) + continue + if not viz.is_running(): + visualizers_to_remove.append(viz) + continue + while viz.is_training_paused() and viz.is_running(): + viz.step(0.0, state=None) + viz.step(dt, state=None) + except Exception as exc: + logger.error(f"Error stepping visualizer '{type(viz).__name__}': {exc}") + visualizers_to_remove.append(viz) + + for viz in visualizers_to_remove: + try: + viz.close() + self._visualizers.remove(viz) + logger.info(f"Removed visualizer: {type(viz).__name__}") + except Exception as exc: + logger.error(f"Error closing visualizer: {exc}") + def play(self) -> None: """Start or resume the simulation.""" self.physics_manager.play() diff --git a/source/isaaclab/isaaclab/sim/spawners/materials/visual_materials.py b/source/isaaclab/isaaclab/sim/spawners/materials/visual_materials.py index 9f205952d3e..e9d6db9fa8c 100644 --- a/source/isaaclab/isaaclab/sim/spawners/materials/visual_materials.py +++ b/source/isaaclab/isaaclab/sim/spawners/materials/visual_materials.py @@ -110,179 +110,6 @@ def spawn_preview_surface(prim_path: str, cfg: visual_materials_cfg.PreviewSurfa return prim -@clone -def spawn_from_mdl_file( - prim_path: str, cfg: visual_materials_cfg.MdlFileCfg | visual_materials_cfg.GlassMdlCfg -) -> Usd.Prim: - """Load a material from its MDL file and override the settings with the given config. - - NVIDIA's `Material Definition Language (MDL) `__ - is a language for defining physically-based materials. The MDL file format is a binary format - that can be loaded by Omniverse and other applications such as Adobe Substance Designer. - To learn more about MDL, see the `documentation `_. - - The function calls the USD command `CreateMdlMaterialPrim`_ to create the prim. - - .. _CreateMdlMaterialPrim: https://docs.omniverse.nvidia.com/kit/docs/omni.usd/latest/omni.usd.commands/omni.usd.commands.CreateMdlMaterialPrimCommand.html - - .. note:: - This function is decorated with :func:`clone` that resolves prim path into list of paths - if the input prim path is a regex pattern. This is done to support spawning multiple assets - from a single and cloning the USD prim at the given path expression. - - Args: - prim_path: The prim path or pattern to spawn the asset at. If the prim path is a regex pattern, - then the asset is spawned at all the matching prim paths. - cfg: The configuration instance. - - Returns: - The created prim. - - Raises: - ValueError: If a prim already exists at the given path. - """ - # get stage handle - stage = get_current_stage() - - # spawn material if it doesn't exist. - if not stage.GetPrimAtPath(prim_path).IsValid(): - # extract material name from path - material_name = cfg.mdl_path.split("/")[-1].split(".")[0] - CreateMdlMaterialPrimCommand( - mtl_url=cfg.mdl_path.format(NVIDIA_NUCLEUS_DIR=NVIDIA_NUCLEUS_DIR), - mtl_name=material_name, - mtl_path=prim_path, - stage=stage, - select_new_prim=False, - ).do() - else: - raise ValueError(f"A prim already exists at path: '{prim_path}'.") - # obtain prim - prim = stage.GetPrimAtPath(f"{prim_path}/Shader") - # check prim is valid - if not prim.IsValid(): - raise ValueError(f"Failed to create MDL material at path: '{prim_path}'.") - # apply properties - cfg = cfg.to_dict() # type: ignore - del cfg["func"] - del cfg["mdl_path"] - for attr_name, attr_value in cfg.items(): - safe_set_attribute_on_usd_prim(prim, f"inputs:{attr_name}", attr_value, camel_case=False) - # return prim - return prim -# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). -# All rights reserved. -# -# SPDX-License-Identifier: BSD-3-Clause - -from __future__ import annotations - -import logging -from typing import TYPE_CHECKING - -from omni.usd.commands import CreateMdlMaterialPrimCommand, CreateShaderPrimFromSdrCommand -from pxr import Usd, UsdShade - -from isaaclab.sim.utils import clone, safe_set_attribute_on_usd_prim -from isaaclab.sim.utils.stage import get_current_stage -from isaaclab.utils.assets import NVIDIA_NUCLEUS_DIR - -if TYPE_CHECKING: - from . import visual_materials_cfg - -# import logger -logger = logging.getLogger(__name__) - - -@clone -def spawn_preview_surface(prim_path: str, cfg: visual_materials_cfg.PreviewSurfaceCfg) -> Usd.Prim: - """Create a preview surface prim and override the settings with the given config. - - A preview surface is a physically-based surface that handles simple shaders while supporting - both *specular* and *metallic* workflows. All color inputs are in linear color space (RGB). - For more information, see the `documentation `__. - - The function calls the USD command `CreateShaderPrimFromSdrCommand`_ to create the prim. - - .. _CreateShaderPrimFromSdrCommand: https://docs.omniverse.nvidia.com/kit/docs/omni.usd/latest/omni.usd.commands/omni.usd.commands.CreateShaderPrimFromSdrCommand.html - - .. note:: - This function is decorated with :func:`clone` that resolves prim path into list of paths - if the input prim path is a regex pattern. This is done to support spawning multiple assets - from a single and cloning the USD prim at the given path expression. - - Args: - prim_path: The prim path or pattern to spawn the asset at. If the prim path is a regex pattern, - then the asset is spawned at all the matching prim paths. - cfg: The configuration instance. - - Returns: - The created prim. - - Raises: - ValueError: If a prim already exists at the given path. - """ - # get stage handle - stage = get_current_stage() - - # spawn material if it doesn't exist. - if not stage.GetPrimAtPath(prim_path).IsValid(): - # note: we don't use Omniverse's CreatePreviewSurfaceMaterialPrimCommand - # since it does not support USD stage as an argument. The created material - # in that case is always the one from USD Context which makes it difficult to - # handle scene creation on a custom stage. - material_prim = UsdShade.Material.Define(stage, prim_path) - if material_prim: - try: - shader_prim = CreateShaderPrimFromSdrCommand( - parent_path=prim_path, - identifier="UsdPreviewSurface", - stage_or_context=stage, - name="Shader", - ).do() - except TypeError: - shader_prim = CreateShaderPrimFromSdrCommand( - parent_path=prim_path, - identifier="UsdPreviewSurface", - stage_or_context=stage, - ).do() - # bind the shader graph to the material - if shader_prim: - surface_out = shader_prim.GetOutput("surface") - if surface_out: - material_prim.CreateSurfaceOutput().ConnectToSource(surface_out) - - displacement_out = shader_prim.GetOutput("displacement") - if displacement_out: - material_prim.CreateDisplacementOutput().ConnectToSource(displacement_out) - else: - raise ValueError(f"Failed to create preview surface shader at path: '{prim_path}'.") - else: - raise ValueError(f"A prim already exists at path: '{prim_path}'.") - - # obtain prim - prim = None - if shader_prim: - if hasattr(shader_prim, "GetPrim"): - prim = shader_prim.GetPrim() - elif hasattr(shader_prim, "IsValid"): - prim = shader_prim - elif hasattr(shader_prim, "GetPath"): - prim = stage.GetPrimAtPath(str(shader_prim.GetPath())) - if prim is None or not prim.IsValid(): - prim = stage.GetPrimAtPath(f"{prim_path}/Shader") - # check prim is valid - if not prim.IsValid(): - raise ValueError(f"Failed to create preview surface material at path: '{prim_path}'.") - # apply properties - cfg = cfg.to_dict() # type: ignore - del cfg["func"] - for attr_name, attr_value in cfg.items(): - safe_set_attribute_on_usd_prim(prim, f"inputs:{attr_name}", attr_value, camel_case=True) - - return prim - - @clone def spawn_from_mdl_file( prim_path: str, cfg: visual_materials_cfg.MdlFileCfg | visual_materials_cfg.GlassMdlCfg diff --git a/source/isaaclab/isaaclab/visualizers/rerun_visualizer.py b/source/isaaclab/isaaclab/visualizers/rerun_visualizer.py index 25d84db9424..fca2ad3c40b 100644 --- a/source/isaaclab/isaaclab/visualizers/rerun_visualizer.py +++ b/source/isaaclab/isaaclab/visualizers/rerun_visualizer.py @@ -176,6 +176,9 @@ def initialize(self, scene_data_provider: SceneDataProvider) -> None: raise def step(self, dt: float, state: Any | None = None) -> None: + if not self._is_initialized or self._viewer is None or self._scene_data_provider is None: + return + self._state = self._scene_data_provider.get_newton_state(self._env_ids) self._sim_time += dt diff --git a/source/isaaclab/isaaclab/visualizers/visualizer.py b/source/isaaclab/isaaclab/visualizers/visualizer.py index 2106d81e4c3..517ed7bfe01 100644 --- a/source/isaaclab/isaaclab/visualizers/visualizer.py +++ b/source/isaaclab/isaaclab/visualizers/visualizer.py @@ -7,6 +7,7 @@ from __future__ import annotations +import logging from abc import ABC, abstractmethod from typing import TYPE_CHECKING, Any @@ -16,6 +17,9 @@ from .visualizer_cfg import VisualizerCfg +logger = logging.getLogger(__name__) + + class Visualizer(ABC): """Base class for all visualizer backends. @@ -80,6 +84,25 @@ def supports_live_plots(self) -> bool: """Check if visualizer supports LivePlots.""" return False + def get_visualized_env_ids(self) -> list[int] | None: + """Return env IDs this visualizer is displaying, if any.""" + return getattr(self, "_env_ids", None) + + def _compute_visualized_env_ids(self) -> list[int] | None: + """Compute which env indices to show from config.""" + if self._scene_data_provider is None: + return None + num_envs = self._scene_data_provider.get_metadata().get("num_envs", 0) + if num_envs <= 0: + logger.warning( + "[Visualizer] num_envs is 0 or missing from provider metadata; partial visualization disabled." + ) + return None + env_ids_cfg = getattr(self.cfg, "env_ids", None) + if env_ids_cfg is not None and len(env_ids_cfg) > 0: + return [i for i in env_ids_cfg if 0 <= i < num_envs] + return None + def get_rendering_dt(self) -> float | None: """Get rendering time step. Returns None to use interface default.""" return None diff --git a/source/isaaclab/isaaclab/visualizers/visualizer_cfg.py b/source/isaaclab/isaaclab/visualizers/visualizer_cfg.py index a2558c45882..7388b837b85 100644 --- a/source/isaaclab/isaaclab/visualizers/visualizer_cfg.py +++ b/source/isaaclab/isaaclab/visualizers/visualizer_cfg.py @@ -47,7 +47,7 @@ class VisualizerCfg: camera_target: tuple[float, float, float] = (0.0, 0.0, 0.0) """Initial camera target/look-at point (x, y, z) in world coordinates.""" - env_ids: list[int] | None = [0] + env_ids: list[int] | None = None """If set, only these env indices are shown; all other envs are filtered from visualization. This improves performance, particularly for large-scale training, by limiting which From 8b539e774cd155064bcc083146e919104817a90a Mon Sep 17 00:00:00 2001 From: Matthew Trepte Date: Tue, 10 Feb 2026 21:06:32 +0000 Subject: [PATCH 45/46] fixes --- source/isaaclab/isaaclab/envs/mdp/events.py | 2 +- .../ov_scene_data_provider.py | 11 ++++++-- .../isaaclab/sim/simulation_context.py | 12 +++++--- .../isaaclab/visualizers/newton_visualizer.py | 5 ++++ .../isaaclab/visualizers/ov_visualizer.py | 28 +++++++++++++------ .../isaaclab/visualizers/rerun_visualizer.py | 26 ++++++----------- .../isaaclab/visualizers/visualizer_cfg.py | 5 ++-- .../test/envs/test_env_rendering_logic.py | 7 ++--- 8 files changed, 55 insertions(+), 41 deletions(-) diff --git a/source/isaaclab/isaaclab/envs/mdp/events.py b/source/isaaclab/isaaclab/envs/mdp/events.py index 3112924c677..8b7883aa1a4 100644 --- a/source/isaaclab/isaaclab/envs/mdp/events.py +++ b/source/isaaclab/isaaclab/envs/mdp/events.py @@ -532,7 +532,7 @@ def randomize_physics_scene_gravity( This function uses CPU tensors to assign gravity. """ # get the current gravity - gravity = torch.tensor(env.sim.cfg.gravity, device="cpu").unsqueeze(0) + gravity = torch.tensor(env.sim.cfg.physics.gravity, device="cpu").unsqueeze(0) dist_param_0 = torch.tensor(gravity_distribution_params[0], device="cpu") dist_param_1 = torch.tensor(gravity_distribution_params[1], device="cpu") gravity = _randomize_prop_by_op( diff --git a/source/isaaclab/isaaclab/sim/scene_data_providers/ov_scene_data_provider.py b/source/isaaclab/isaaclab/sim/scene_data_providers/ov_scene_data_provider.py index 258c6da2b1f..5cb5e57bade 100644 --- a/source/isaaclab/isaaclab/sim/scene_data_providers/ov_scene_data_provider.py +++ b/source/isaaclab/isaaclab/sim/scene_data_providers/ov_scene_data_provider.py @@ -72,6 +72,7 @@ def __init__(self, visualizer_cfgs: list[Any] | None, stage, simulation_context) self._rigid_body_view = None self._articulation_view = None self._xform_views: dict[str, Any] = {} + self._xform_view_failures: set[str] = set() self._view_body_index_map: dict[str, list[int]] = {} # Scene info: set via set_num_envs/set_env_origins after creation (by sim, from env). @@ -84,7 +85,7 @@ def __init__(self, visualizer_cfgs: list[Any] | None, stage, simulation_context) # Metadata: only fixed backend info. num_envs/env_origins come from get_num_envs()/self._env_origins. self._metadata = { "physics_backend": "omni", - "gravity_vector": tuple(self._simulation_context.cfg.gravity), + "gravity_vector": tuple(self._simulation_context.cfg.physics.gravity), "clone_physics_only": False, } self._up_axis = UsdGeom.GetStageUpAxis(self._stage) @@ -238,6 +239,8 @@ def _setup_rigid_body_view(self) -> None: Uses body paths extracted from Newton model to create PhysX tensor API view for reading rigid body transforms. """ + if self._physics_sim_view is None: + return if not self._rigid_body_paths: return try: @@ -250,6 +253,8 @@ def _setup_rigid_body_view(self) -> None: def _setup_articulation_view(self) -> None: """Create PhysX ArticulationView from Newton's articulation paths.""" + if self._physics_sim_view is None: + return if not self._articulation_paths: return try: @@ -402,6 +407,8 @@ def _apply_xform_poses(self, positions: Any, orientations: Any, covered: Any, xf count = 0 for idx in uncovered: path = self._rigid_body_paths[idx] + if path in self._xform_view_failures: + continue try: if path not in self._xform_views: self._xform_views[path] = XformPrimView( @@ -416,6 +423,7 @@ def _apply_xform_poses(self, positions: Any, orientations: Any, covered: Any, xf xform_mask[idx] = True count += 1 except Exception: + self._xform_view_failures.add(path) continue return count @@ -538,7 +546,6 @@ def update(self, env_ids: list[int] | None = None) -> None: return self._refresh_newton_model_if_needed() - try: import warp as wp diff --git a/source/isaaclab/isaaclab/sim/simulation_context.py b/source/isaaclab/isaaclab/sim/simulation_context.py index e6da2ad33e3..63a092eb230 100644 --- a/source/isaaclab/isaaclab/sim/simulation_context.py +++ b/source/isaaclab/isaaclab/sim/simulation_context.py @@ -228,9 +228,6 @@ def set_scene_info(self, scene: Any) -> None: if callable(set_env_origins): set_env_origins(env_origins) - if not self._visualizers: - self.initialize_visualizers() - def _create_default_visualizer_configs(self, requested_visualizers: list[str]) -> list: """Create default visualizer configs for requested types.""" default_configs = [] @@ -352,6 +349,9 @@ def reset(self, soft: bool = False) -> None: viz.reset(soft) # Start the timeline so the play button is pressed self.physics_manager.play() + if not self._visualizers: + # Initialize visualizers after PhysX sim view is ready. + self.initialize_visualizers() self._is_playing = True self._is_stopped = False @@ -378,7 +378,8 @@ def update_visualizers(self, dt: float) -> None: if not self._visualizers: return - self.physics_manager.forward() + if any(type(v).__name__ == "OVVisualizer" for v in self._visualizers): + self.physics_manager.forward() self._visualizer_step_counter += 1 if self._scene_data_provider: env_ids_union: list[int] = [] @@ -395,9 +396,11 @@ def update_visualizers(self, dt: float) -> None: if viz.is_rendering_paused(): continue if getattr(viz, "is_closed", False): + print(f"[SimulationContext] Visualizer closed: {type(viz).__name__}") visualizers_to_remove.append(viz) continue if not viz.is_running(): + print(f"[SimulationContext] Visualizer not running: {type(viz).__name__}") visualizers_to_remove.append(viz) continue while viz.is_training_paused() and viz.is_running(): @@ -405,6 +408,7 @@ def update_visualizers(self, dt: float) -> None: viz.step(dt, state=None) except Exception as exc: logger.error(f"Error stepping visualizer '{type(viz).__name__}': {exc}") + print(f"[SimulationContext] Visualizer step error: {type(viz).__name__}: {exc}") visualizers_to_remove.append(viz) for viz in visualizers_to_remove: diff --git a/source/isaaclab/isaaclab/visualizers/newton_visualizer.py b/source/isaaclab/isaaclab/visualizers/newton_visualizer.py index 547dbd6f953..a33b25b7d92 100644 --- a/source/isaaclab/isaaclab/visualizers/newton_visualizer.py +++ b/source/isaaclab/isaaclab/visualizers/newton_visualizer.py @@ -273,6 +273,11 @@ def initialize(self, scene_data_provider: SceneDataProvider) -> None: self._viewer.renderer.sky_lower = self.cfg.sky_lower_color self._viewer.renderer._light_color = self.cfg.light_color + logger.info( + "[NewtonVisualizer] Initialized (camera: pos=%s, target=%s)", + self.cfg.camera_position, + self.cfg.camera_target, + ) self._is_initialized = True def step(self, dt: float, state: Any | None = None) -> None: diff --git a/source/isaaclab/isaaclab/visualizers/ov_visualizer.py b/source/isaaclab/isaaclab/visualizers/ov_visualizer.py index f7ef5a43b16..995497598c7 100644 --- a/source/isaaclab/isaaclab/visualizers/ov_visualizer.py +++ b/source/isaaclab/isaaclab/visualizers/ov_visualizer.py @@ -56,12 +56,9 @@ def initialize(self, scene_data_provider: SceneDataProvider) -> None: if self._env_ids: logger.warning("[OVVisualizer] env_ids filtering is not supported yet. All environments will be shown.") self._env_ids = None - num_envs = metadata.get("num_envs", 0) - physics_backend = metadata.get("physics_backend", "unknown") - logger.info( - f"[OVVisualizer] Initialized ({num_envs} envs, {physics_backend} physics)" - + (f", showing {len(self._env_ids)} envs" if self._env_ids is not None else "") - ) + cam_pos = self.cfg.camera_position + cam_target = self.cfg.camera_target + logger.info(f"[OVVisualizer] Initialized (camera: pos={cam_pos}, target={cam_target})") self._is_initialized = True @@ -70,6 +67,14 @@ def step(self, dt: float, state: Any | None = None) -> None: return self._sim_time += dt self._step_counter += 1 + try: + import omni.kit.app + + app = omni.kit.app.get_app() + if app is not None and app.is_running(): + app.update() + except Exception: + pass def close(self) -> None: if not self._is_initialized: @@ -80,9 +85,15 @@ def close(self) -> None: self._is_initialized = False def is_running(self) -> bool: - if self._simulation_app is None: + if self._simulation_app is not None: + return self._simulation_app.is_running() + try: + import omni.kit.app + + app = omni.kit.app.get_app() + return app is not None and app.is_running() + except Exception: return False - return self._simulation_app.is_running() def is_training_paused(self) -> bool: return False @@ -147,7 +158,6 @@ def _setup_viewport(self, usd_stage, metadata: dict) -> None: docked=True, ) - logger.info(f"[OVVisualizer] Created viewport '{self.cfg.viewport_name}'") asyncio.ensure_future(self._dock_viewport_async(self.cfg.viewport_name, dock_pos)) self._create_and_assign_camera(usd_stage) else: diff --git a/source/isaaclab/isaaclab/visualizers/rerun_visualizer.py b/source/isaaclab/isaaclab/visualizers/rerun_visualizer.py index fca2ad3c40b..4cba32912ef 100644 --- a/source/isaaclab/isaaclab/visualizers/rerun_visualizer.py +++ b/source/isaaclab/isaaclab/visualizers/rerun_visualizer.py @@ -101,9 +101,6 @@ def initialize(self, scene_data_provider: SceneDataProvider) -> None: self._state = scene_data_provider.get_newton_state(self._env_ids) try: - if self.cfg.record_to_rrd: - logger.info(f"[RerunVisualizer] Recording enabled to: {self.cfg.record_to_rrd}") - address = None if self.cfg.bind_address: import shutil @@ -126,6 +123,12 @@ def initialize(self, scene_data_provider: SceneDataProvider) -> None: if self.cfg.open_browser: cmd.append("--web-viewer") self._rerun_server_process = subprocess.Popen(cmd) + logger.info( + "[RerunVisualizer] Server bind %s:%s, web %s", + self.cfg.bind_address, + self.cfg.grpc_port, + self.cfg.web_port, + ) address = f"rerun+http://127.0.0.1:{self.cfg.grpc_port}/proxy" self._viewer = NewtonViewerRerun( @@ -142,10 +145,9 @@ def initialize(self, scene_data_provider: SceneDataProvider) -> None: self._viewer.set_model(self._model) self._viewer.set_world_offsets((0.0, 0.0, 0.0)) + cam_pos = self.cfg.camera_position + cam_target = self.cfg.camera_target try: - cam_pos = self.cfg.camera_position - cam_target = self.cfg.camera_target - blueprint = rrb.Blueprint( rrb.Spatial3DView( name="3D View", @@ -158,17 +160,10 @@ def initialize(self, scene_data_provider: SceneDataProvider) -> None: collapse_panels=True, ) rr.send_blueprint(blueprint) - - logger.info(f"[RerunVisualizer] Set initial camera view: position={cam_pos}, target={cam_target}") except Exception as exc: logger.warning(f"[RerunVisualizer] Could not set initial camera view: {exc}") - num_envs = metadata.get("num_envs", 0) - physics_backend = metadata.get("physics_backend", "unknown") - msg = f"[RerunVisualizer] Initialized with {num_envs} environments (physics: {physics_backend})" - if self._env_ids is not None: - msg += f", showing {len(self._env_ids)} envs" - logger.info(msg) + logger.info("[RerunVisualizer] Initialized (camera: pos=%s, target=%s)", cam_pos, cam_target) self._is_initialized = True except Exception as exc: @@ -191,10 +186,7 @@ def close(self) -> None: return try: - if self.cfg.record_to_rrd: - logger.info(f"[RerunVisualizer] Finalizing recording to: {self.cfg.record_to_rrd}") self._viewer.close() - logger.info("[RerunVisualizer] Closed successfully.") if self.cfg.record_to_rrd: import os diff --git a/source/isaaclab/isaaclab/visualizers/visualizer_cfg.py b/source/isaaclab/isaaclab/visualizers/visualizer_cfg.py index 7388b837b85..7bfc43198da 100644 --- a/source/isaaclab/isaaclab/visualizers/visualizer_cfg.py +++ b/source/isaaclab/isaaclab/visualizers/visualizer_cfg.py @@ -50,9 +50,8 @@ class VisualizerCfg: env_ids: list[int] | None = None """If set, only these env indices are shown; all other envs are filtered from visualization. - This improves performance, particularly for large-scale training, by limiting which - environments are sent to visualizers. Backend support varies (e.g., OV ignores - this for now). + This improves performance, particularly for large-scale training, by reducing scene updates sent to visualizers. + Note, OV visualizer doesn't not currently support this. """ def get_visualizer_type(self) -> str | None: diff --git a/source/isaaclab/test/envs/test_env_rendering_logic.py b/source/isaaclab/test/envs/test_env_rendering_logic.py index 1fdfbbbb244..d5cfa5de731 100644 --- a/source/isaaclab/test/envs/test_env_rendering_logic.py +++ b/source/isaaclab/test/envs/test_env_rendering_logic.py @@ -16,7 +16,6 @@ import pytest import torch from isaaclab_physx.physics import IsaacEvents, PhysxCfg -from isaaclab_physx.visualizers import RenderMode import isaaclab.sim as sim_utils from isaaclab.envs import ( @@ -172,10 +171,8 @@ def test_env_rendering_logic(env_type, render_interval, physics_callback, render # Without it, the test will exit after the environment is closed env.sim._app_control_on_stop_handle = None # type: ignore - # check that we are in partial rendering mode for the environment - # this is enabled due to app launcher setting "enable_cameras=True" - # Access render mode through the first visualizer (OVVisualizer) - assert env.sim.visualizers[0].render_mode == RenderMode.PARTIAL_RENDERING + # Ensure at least one visualizer exists (OVVisualizer when running with GUI/cameras) + assert env.sim.visualizers # add physics callback via physics manager (IsaacEvents is PhysX-specific) physics_handle = env.sim.physics_manager.register_callback( From 21321412a9b185ad4a0017b9abf37e896d0abeea Mon Sep 17 00:00:00 2001 From: Matthew Trepte Date: Tue, 10 Feb 2026 21:15:01 +0000 Subject: [PATCH 46/46] remove files --- scripts/warp_renderer/example.py | 147 -------- .../isaaclab/isaaclab/renderers/__init__.py | 6 - .../renderers/newton_warp_renderer.py | 172 ---------- .../renderers/newton_warp_renderer_direct.py | 319 ------------------ .../configs_custom_reward_thresholds.yaml | 14 - 5 files changed, 658 deletions(-) delete mode 100644 scripts/warp_renderer/example.py delete mode 100644 source/isaaclab/isaaclab/renderers/__init__.py delete mode 100644 source/isaaclab/isaaclab/renderers/newton_warp_renderer.py delete mode 100644 source/isaaclab/isaaclab/renderers/newton_warp_renderer_direct.py delete mode 100644 source/isaaclab_tasks/test/benchmarking/configs_custom_reward_thresholds.yaml diff --git a/scripts/warp_renderer/example.py b/scripts/warp_renderer/example.py deleted file mode 100644 index fe00a37cc3e..00000000000 --- a/scripts/warp_renderer/example.py +++ /dev/null @@ -1,147 +0,0 @@ -# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). -# All rights reserved. -# -# SPDX-License-Identifier: BSD-3-Clause - -import argparse -import contextlib -import time - -from isaaclab.app import AppLauncher - - -@contextlib.contextmanager -def measure_time(title: str, iterations: int = 1): - start_time = time.perf_counter_ns() - yield - end_time = time.perf_counter_ns() - print(f"[BENCHMARK] {title}: {(end_time - start_time) / iterations / 1e6:.2f} ms") - - -@contextlib.contextmanager -def launch_app(args): - with measure_time("App start time"): - app_launcher = AppLauncher(args) - yield app_launcher.app - if app_launcher.app: - app_launcher.app.close() - - -parser = argparse.ArgumentParser(description="Benchmark Warp Raytrace") -parser.add_argument("--num_envs", type=int, default=32, help="Number of robots to simulate") -parser.add_argument("--save_images", action="store_true", help="Save Sensor Images") -parser.add_argument("--steps", type=int, default=2000, help="Number of steps to simulate") - -AppLauncher.add_app_launcher_args(parser) -args, _ = parser.parse_known_args() - -app_launcher = AppLauncher(args) - -with measure_time("Imports time"): - import torch - - import isaaclab.sim as isaaclab_sim - from isaaclab.assets import Articulation, ArticulationCfg, AssetBaseCfg - from isaaclab.renderers import NewtonWarpRenderer as NewtonWarpRenderer - from isaaclab.scene import InteractiveScene, InteractiveSceneCfg - from isaaclab.sensors import TiledCamera, TiledCameraCfg - from isaaclab.utils import configclass - - from isaaclab_assets import ANYMAL_D_CFG - - -@configclass -class SceneCfg(InteractiveSceneCfg): - ground = AssetBaseCfg(prim_path="/World/defaultGroundPlane", spawn=isaaclab_sim.GroundPlaneCfg()) - dome_light = AssetBaseCfg( - prim_path="/World/Light", - spawn=isaaclab_sim.DomeLightCfg(intensity=3000.0, color=(0.75, 0.75, 0.75)), - ) - robot: ArticulationCfg = ANYMAL_D_CFG - robot.prim_path = "{ENV_REGEX_NS}/Robot" - - -def run_simulator( - sim: isaaclab_sim.SimulationContext, - scene: InteractiveScene, - num_steps: int, - renderer: NewtonWarpRenderer, - save_images: bool, -): - robot: Articulation = scene["robot"] - for step in range(num_steps): - if step % 500 == 0: - # reset the scene entities root state we offset the root state by the origin since the states are - # written in simulation world frame if this is not done, then the robots will be spawned at - # the (0, 0, 0) of the simulation world - - root_state = robot.data.default_root_state.clone() - root_state[:, :3] += scene.env_origins - robot.write_root_pose_to_sim(root_state[:, :7]) - robot.write_root_velocity_to_sim(root_state[:, 7:]) - # set joint positions with some noise - joint_pos, joint_vel = robot.data.default_joint_pos.clone(), robot.data.default_joint_vel.clone() - joint_pos += torch.rand_like(joint_pos) * 0.1 - robot.write_joint_state_to_sim(joint_pos, joint_vel) - # clear internal buffers - scene.reset() - - # Apply random action - efforts = torch.randn_like(robot.data.joint_pos) * 5.0 - robot.set_joint_effort_target(efforts) - - scene.write_data_to_sim() - sim.step() - scene.update(sim.get_physics_dt()) - - renderer.update() - renderer.render_all() - if save_images: - renderer.camera_manager.save_images(f"__warp_renderer/%s_rgb.{step:04d}.png") - - -def main(): - with measure_time("Simulation Context creation time"): - sim_cfg = isaaclab_sim.SimulationCfg(device="cuda:0") - sim = isaaclab_sim.SimulationContext(sim_cfg) - - sim.set_camera_view((2.5, 0.0, 4.0), (0.0, 0.0, 2.0)) - - with measure_time("Scene creation time"): - scene_cfg = SceneCfg(num_envs=args.num_envs, env_spacing=2.0) - scene = InteractiveScene(scene_cfg) - - tiled_camera_cfg: TiledCameraCfg = TiledCameraCfg( - prim_path="/World/envs/env_.*/Camera", - offset=TiledCameraCfg.OffsetCfg( - pos=(-3.0, 0.0, 1.0), - rot=(0.0, 0.0, 0.0, 1.0), - convention="world", - ), - data_types=["rgb"], - spawn=isaaclab_sim.PinholeCameraCfg( - focal_length=24.0, - focus_distance=400.0, - horizontal_aperture=20.955, - clipping_range=(0.1, 20.0), - ), - width=400, - height=400, - ) - scene.sensors["tiled_camera"] = TiledCamera(tiled_camera_cfg) - - renderer = NewtonWarpRenderer(scene) - - # stage = isaaclab_sim.get_current_stage() - # stage.Export("/home/dhasenbring/development/isaac/IsaacLab/stage.usda") - - with measure_time("Sim start time"): - sim.reset() - - with measure_time("Average sim step time", iterations=args.steps): - run_simulator(sim, scene, args.steps, renderer, args.save_images) - - -if __name__ == "__main__": - main() - app_launcher.app.close() diff --git a/source/isaaclab/isaaclab/renderers/__init__.py b/source/isaaclab/isaaclab/renderers/__init__.py deleted file mode 100644 index 1d73e820b42..00000000000 --- a/source/isaaclab/isaaclab/renderers/__init__.py +++ /dev/null @@ -1,6 +0,0 @@ -# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). -# All rights reserved. -# -# SPDX-License-Identifier: BSD-3-Clause - -from .newton_warp_renderer import NewtonWarpRenderer diff --git a/source/isaaclab/isaaclab/renderers/newton_warp_renderer.py b/source/isaaclab/isaaclab/renderers/newton_warp_renderer.py deleted file mode 100644 index 19639fd8e9f..00000000000 --- a/source/isaaclab/isaaclab/renderers/newton_warp_renderer.py +++ /dev/null @@ -1,172 +0,0 @@ -# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). -# All rights reserved. -# -# SPDX-License-Identifier: BSD-3-Clause - -import os -from dataclasses import dataclass, field - -import newton -import warp as wp - -from pxr import Usd - -import isaaclab.sim as isaaclab_sim -from isaaclab.scene import InteractiveScene -from isaaclab.sensors import TiledCamera - - -class CameraManager: - @dataclass - class CameraData: - camera_rays: wp.array(dtype=wp.vec3f, ndim=4) = None - color_image: wp.array(dtype=wp.uint32, ndim=4) = None - prims: list[Usd.Prim] = field(default_factory=lambda: []) - width: int = 100 - height: int = 100 - - def __init__(self, scene: InteractiveScene): - self.render_context: newton.sensors.SensorTiledCamera.RenderContext | None = None - self.scene = scene - self.num_cameras = 1 - self.camera_data: dict[str, CameraManager.CameraData] = {} - - for name, sensor in self.scene.sensors.items(): - camera_data = CameraManager.CameraData() - camera_data.prims = isaaclab_sim.find_matching_prims(sensor.cfg.prim_path) - if isinstance(sensor, TiledCamera): - camera_data.width = sensor.cfg.width - camera_data.height = sensor.cfg.height - self.camera_data[name] = camera_data - - def create_outputs(self, render_context: newton.sensors.SensorTiledCamera.RenderContext): - self.render_context = render_context - for name in self.scene.sensors: - camera_fovs = wp.array([20.0] * self.num_cameras, dtype=wp.float32) - width = self.camera_data[name].width - height = self.camera_data[name].height - self.camera_data[name].camera_rays = render_context.utils.compute_pinhole_camera_rays( - width, height, camera_fovs - ) - self.camera_data[name].color_image = render_context.create_color_image_output( - width, height, self.num_cameras - ) - - def get_camera_transforms(self, camera_data: CameraData) -> wp.array(dtype=wp.transformf): - camera_transforms = [] - for prim in camera_data.prims: - camera_transforms.append(self.__resolve_camera_transform(prim)) - return wp.array([camera_transforms], dtype=wp.transformf) - - def save_images(self, filename: str): - if self.render_context is None: - return - - for name, camera_data in self.camera_data.items(): - color_data = self.render_context.utils.flatten_color_image_to_rgba(camera_data.color_image) - - from PIL import Image - - os.makedirs(os.path.dirname(filename), exist_ok=True) - Image.fromarray(color_data.numpy()).save(filename % name) - - def __resolve_camera_transform(self, prim: Usd.Prim) -> wp.transformf: - position, orientation = isaaclab_sim.resolve_prim_pose(prim) - return wp.transformf(position, wp.quatf(orientation[1], -orientation[2], -orientation[3], orientation[0])) - # position, orientation = isaaclab_sim.resolve_prim_pose(prim) - # t = torch.tensor(orientation, dtype=torch.float32, device="cpu").unsqueeze(0) - # t = convert_camera_frame_orientation_convention(t) - # orientation = t.squeeze(0).cpu().numpy() - # return wp.transformf(position, wp.quatf(orientation)) - - -class NewtonWarpRenderer: - def __init__(self, scene: InteractiveScene): - self.scene = scene - - builder = newton.ModelBuilder() - builder.add_usd(isaaclab_sim.get_current_stage(), ignore_paths=[r"/World/envs/.*"]) - for world_id in range(scene.num_envs): - builder.begin_world() - for name, articulation in self.scene.articulations.items(): - path = articulation.cfg.prim_path.replace(".*", str(world_id)) - builder.add_usd(isaaclab_sim.get_current_stage(), root_path=path) - builder.end_world() - - self.newton_model = builder.finalize() - self.newton_state = self.newton_model.state() - - self.physx_to_newton_body_mapping: dict[str, wp.array(dtype=wp.int32, ndim=2)] = {} - - self.camera_manager = CameraManager(scene) - self.newton_sensor = newton.sensors.SensorTiledCamera(self.newton_model) - self.camera_manager.create_outputs(self.newton_sensor.render_context) - - def update(self): - self.__update_mapping() - for name, articulation in self.scene.articulations.items(): - if mapping := self.physx_to_newton_body_mapping.get(name): - physx_pos = wp.from_torch(articulation.data.body_pos_w) - physx_quat = wp.from_torch(articulation.data.body_quat_w) - inputs = [mapping, self.newton_model.body_world, physx_pos, physx_quat, self.newton_state.body_q] - wp.launch( - NewtonWarpRenderer.__update_transforms, - mapping.shape, - inputs, - ) - - def render(self, sensor_name: str): - if camera_data := self.camera_manager.camera_data.get(sensor_name): - self.__render(camera_data) - - def render_all(self): - for name, camera_data in self.camera_manager.camera_data.items(): - self.__render(camera_data) - - def __render(self, camera_data: CameraManager.CameraData): - camera_transforms = self.camera_manager.get_camera_transforms(camera_data) - self.newton_sensor.render( - self.newton_state, - camera_transforms, - camera_data.camera_rays, - camera_data.color_image, - ) - - def __update_mapping(self): - if self.physx_to_newton_body_mapping: - return - - self.physx_to_newton_body_mapping.clear() - for name, articulation in self.scene.articulations.items(): - articulation_mapping = [] - for prim in isaaclab_sim.find_matching_prims(articulation.cfg.prim_path): - body_indices = [] - for body_name in articulation.body_names: - prim_path = prim.GetPath().AppendChild(body_name).pathString - body_indices.append(self.newton_model.body_key.index(prim_path)) - articulation_mapping.append(body_indices) - self.physx_to_newton_body_mapping[name] = wp.array( - articulation_mapping, - dtype=wp.int32, - ) - - @wp.kernel(enable_backward=False) - def __update_transforms( - mapping: wp.array(dtype=wp.int32, ndim=2), - newton_body_world: wp.array(dtype=wp.int32), - physx_pos: wp.array(dtype=wp.float32, ndim=3), - physx_quat: wp.array(dtype=wp.float32, ndim=3), - out_transform: wp.array(dtype=wp.transformf), - ): - physx_world_id, physx_body_id = wp.tid() - - newton_body_index = mapping[physx_world_id, physx_body_id] - newton_world_id = newton_body_world[newton_body_index] - - pos_raw = physx_pos[newton_world_id, physx_body_id] - pos = wp.vec3f(pos_raw[0], pos_raw[1], pos_raw[2]) - - quat_raw = physx_quat[newton_world_id, physx_body_id] - quat = wp.quatf(quat_raw[1], quat_raw[2], quat_raw[3], quat_raw[0]) - - out_transform[newton_body_index] = wp.transformf(pos, quat) diff --git a/source/isaaclab/isaaclab/renderers/newton_warp_renderer_direct.py b/source/isaaclab/isaaclab/renderers/newton_warp_renderer_direct.py deleted file mode 100644 index dfccbb15e28..00000000000 --- a/source/isaaclab/isaaclab/renderers/newton_warp_renderer_direct.py +++ /dev/null @@ -1,319 +0,0 @@ -# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). -# All rights reserved. -# -# SPDX-License-Identifier: BSD-3-Clause - -import re -from dataclasses import dataclass, field - -import numpy as np -import warp as wp -from newton.sensors import SensorTiledCamera - -import usdrt -from pxr import Usd, UsdGeom - -import isaaclab.sim as isaaclab_sim -from isaaclab.renderers.newton_warp_renderer import CameraManager -from isaaclab.scene import InteractiveScene - - -@wp.kernel(enable_backward=False) -def compute_triangle_count( - num_face_counts: wp.int32, face_counts: wp.array(dtype=wp.int32), out_face_offsets: wp.array(dtype=wp.int32) -): - offset = wp.int32(0) - for i in range(num_face_counts): - out_face_offsets[i] = offset - offset += face_counts[i] - out_face_offsets[num_face_counts] = offset - num_face_counts * 2 - - -@wp.kernel(enable_backward=False) -def triangulate_faces( - num_face_counts: wp.int32, - face_counts: wp.array(dtype=wp.int32), - face_indices: wp.array(dtype=wp.int32), - face_offsets: wp.array(dtype=wp.int32), - out_triangles: wp.array(dtype=wp.int32), -): - offset = face_offsets[wp.tid()] - num_triangles = face_counts[wp.tid()] - 2 - tri = wp.atomic_add(face_offsets, num_face_counts + 1, num_triangles * 3) - - for i in range(num_triangles): - out_triangles[tri + i * 3 + 0] = face_indices[offset] - out_triangles[tri + i * 3 + 1] = face_indices[offset + i + 1] - out_triangles[tri + i * 3 + 2] = face_indices[offset + i + 2] - - -@wp.kernel(enable_backward=False) -def update_transforms( - fabric_matrices: wp.fabricarray(dtype=wp.mat44d), - mapping: wp.array(dtype=wp.int32), - transforms: wp.array(dtype=wp.transformf), -): - tid = wp.tid() - if mapping[tid] > -1: - m = fabric_matrices[mapping[tid]] - - orientation = wp.mat33f( - wp.float32(m[0, 0]), - wp.float32(m[1, 0]), - wp.float32(m[2, 0]), - wp.float32(m[0, 1]), - wp.float32(m[1, 1]), - wp.float32(m[2, 1]), - wp.float32(m[0, 2]), - wp.float32(m[1, 2]), - wp.float32(m[2, 2]), - ) - - position = wp.vec3f(wp.float32(m[3, 0]), wp.float32(m[3, 1]), wp.float32(m[3, 2])) - - transforms[tid] = wp.transformf(position, wp.normalize(wp.quat_from_matrix(orientation))) - - -class NewtonWarpRendererDirect: - @dataclass - class PrimData: - is_shared: bool = False - shape_type: SensorTiledCamera.RenderShapeType = SensorTiledCamera.RenderShapeType.NONE - master_prim: Usd.Prim | None = None - prims: list[tuple[int, Usd.Prim]] = field(default_factory=lambda: []) - - def __init__(self, scene: InteractiveScene): - self.prim_data: dict[str, NewtonWarpRendererDirect.PrimData] = {} - self.num_worlds = self.__collect_prims(isaaclab_sim.get_current_stage()) - - shape_transforms = [] - shape_sizes = [] - shape_types = [] - shape_mesh_indices = [] - shape_world_indices = [] - - self.__warp_meshes = [] - self.__fabric_stage_id = None - self.__fabric_selection: usdrt.RtPrimSelection = None - self.__fabric_selection_mapping: list[int] = [] - - for prim_path, prim_data in self.prim_data.items(): - if prim_data.is_shared: - mesh_index = -1 - if prim_data.shape_type == SensorTiledCamera.RenderShapeType.MESH: - mesh_index = len(self.__warp_meshes) - self.__warp_meshes.append(self.__build_mesh(prim_data.master_prim)) - - for world_id, prim in prim_data.prims: - shape_types.append(prim_data.shape_type) - shape_transforms.append(self.__resolve_transform(prim)) - shape_sizes.append(self.__resolve_shape_size(prim_data.shape_type, prim)) - shape_mesh_indices.append(mesh_index) - shape_world_indices.append(world_id) - - self.camera_manager = CameraManager(scene) - - self.render_context = SensorTiledCamera.RenderContext(self.num_worlds) - self.render_context.num_shapes_total = len(shape_transforms) - self.render_context.num_shapes_enabled = self.render_context.num_shapes_total - self.render_context.mesh_ids = wp.array([mesh.id for mesh in self.__warp_meshes], dtype=wp.uint64) - self.render_context.shape_mesh_indices = wp.array(shape_mesh_indices, dtype=wp.int32) - self.render_context.shape_types = wp.array(shape_types, dtype=wp.int32) - self.render_context.mesh_bounds = wp.empty((self.render_context.num_shapes_total, 2), dtype=wp.vec3f, ndim=2) - self.render_context.shape_enabled = wp.array(np.arange(self.render_context.num_shapes_total), dtype=wp.uint32) - self.render_context.shape_sizes = wp.array(shape_sizes, dtype=wp.vec3f) - self.render_context.shape_transforms = wp.array(shape_transforms, dtype=wp.transformf) - self.render_context.shape_materials = wp.array( - np.full(self.render_context.num_shapes_total, fill_value=-1, dtype=np.int32), dtype=wp.int32 - ) - self.render_context.shape_world_index = wp.array(shape_world_indices, dtype=wp.int32) - self.render_context.utils.compute_mesh_bounds() - self.render_context.utils.create_default_light(False) - self.render_context.utils.assign_random_colors_per_shape() - - self.camera_manager.create_outputs(self.render_context) - - def update(self): - self.__update_fabric_selection() - fabric_matrices = wp.fabricarray( - self.__fabric_selection.__fabric_arrays_interface__, "omni:fabric:worldMatrix", dtype=wp.mat44d - ) - wp.launch( - update_transforms, - len(self.__fabric_selection_mapping), - [ - fabric_matrices, - wp.array(self.__fabric_selection_mapping, dtype=wp.int32), - self.render_context.shape_transforms, - ], - ) - - def render(self, sensor_name: str): - if camera_data := self.camera_manager.camera_data.get(sensor_name): - self.__render(camera_data) - - def render_all(self): - for name, camera_data in self.camera_manager.camera_data.items(): - self.__render(camera_data) - - def __render(self, camera_data: CameraManager.CameraData): - self.render_context.render( - self.camera_manager.get_camera_transforms(camera_data), camera_data.camera_rays, camera_data.color_image - ) - - def __update_fabric_selection(self): - stage_id = isaaclab_sim.get_current_stage_id() - if self.__fabric_stage_id != stage_id: - self.__fabric_stage_id = stage_id - self.__fabric_selection = None - - stage = usdrt.Usd.Stage.Attach(stage_id) - - update_mapping = False - if self.__fabric_selection is None: - self.__fabric_selection = stage.SelectPrims( - require_attrs=[(usdrt.Sdf.ValueTypeNames.Matrix4d, "omni:fabric:worldMatrix", usdrt.Usd.Access.Read)], - want_paths=True, - device=wp.get_device().alias, - ) - update_mapping = True - else: - update_mapping = self.__fabric_selection.PrepareForReuse() - - if update_mapping: - self.__fabric_selection_mapping = [] - selection_paths = self.__fabric_selection.GetPaths() - for prim_path, prim_data in self.prim_data.items(): - if prim_data.is_shared: - for world_id, prim in prim_data.prims: - try: - self.__fabric_selection_mapping.append(selection_paths.index(prim_path % world_id)) - except ValueError: - self.__fabric_selection_mapping.append(-1) - - def __collect_prims( - self, stage: Usd.Stage, env_regex: str = r"(?P/World/envs/env_)(?P\d+)(?P/.*)" - ) -> int: - env_pattern = re.compile(env_regex) - - num_worlds = -1 - stage_prims: list[Usd.Prim] = [stage.GetPseudoRoot()] - while stage_prims: - prim = stage_prims.pop(0) - prim_path = prim.GetPath().pathString - - world_id = -1 - if match := env_pattern.match(prim_path): - world_id = int(match.group("id")) - prim_path = match.group("root") + "%d" + match.group("path") - - if world_id > -1: - if world_id > num_worlds: - num_worlds = world_id - - imageable = UsdGeom.Imageable(prim) - if imageable and imageable.ComputeVisibility() == UsdGeom.Tokens.invisible: - continue - - shape_type = SensorTiledCamera.RenderShapeType.NONE - - if prim.IsA(UsdGeom.Mesh): - shape_type = SensorTiledCamera.RenderShapeType.MESH - elif prim.IsA(UsdGeom.Sphere): - shape_type = SensorTiledCamera.RenderShapeType.SPHERE - elif prim.IsA(UsdGeom.Capsule): - shape_type = SensorTiledCamera.RenderShapeType.CAPSULE - elif prim.IsA(UsdGeom.Cube): - shape_type = SensorTiledCamera.RenderShapeType.BOX - elif prim.IsA(UsdGeom.Cylinder): - shape_type = SensorTiledCamera.RenderShapeType.CYLINDER - elif prim.IsA(UsdGeom.Cone): - shape_type = SensorTiledCamera.RenderShapeType.CONE - elif prim.IsA(UsdGeom.Plane): - shape_type = SensorTiledCamera.RenderShapeType.PLANE - - if shape_type != SensorTiledCamera.RenderShapeType.NONE: - if prim_path not in self.prim_data: - self.prim_data[prim_path] = NewtonWarpRendererDirect.PrimData(world_id > -1, shape_type, prim) - self.prim_data[prim_path].prims.append((world_id, prim)) - - if child_prims := prim.GetFilteredChildren(UsdGeom.TraverseInstanceProxies()): - stage_prims.extend(child_prims) - return num_worlds + 1 - - def __build_mesh(self, prim: Usd.Prim): - mesh = UsdGeom.Mesh(prim) - points = wp.array(mesh.GetPointsAttr().Get(), dtype=wp.vec3f) - face_vertex_counts = wp.array(mesh.GetFaceVertexCountsAttr().Get(), dtype=wp.int32) - face_vertex_indices = wp.array(mesh.GetFaceVertexIndicesAttr().Get(), dtype=wp.int32) - - num_face_counts = face_vertex_counts.size - wp_face_offsets = wp.zeros(num_face_counts + 2, dtype=wp.int32) - - wp.launch(kernel=compute_triangle_count, dim=1, inputs=[num_face_counts, face_vertex_counts, wp_face_offsets]) - - num_triangles = wp_face_offsets.numpy()[num_face_counts].item() - wp_triangle_indices = wp.empty(num_triangles * 3, dtype=wp.int32) - - wp.launch( - kernel=triangulate_faces, - dim=num_face_counts, - inputs=[num_face_counts, face_vertex_counts, face_vertex_indices, wp_face_offsets, wp_triangle_indices], - ) - - return wp.Mesh(points=points, velocities=None, indices=wp_triangle_indices) - - def __resolve_transform(self, prim: Usd.Prim) -> wp.transformf: - position, orientation = isaaclab_sim.resolve_prim_pose(prim) - return wp.transformf(position, wp.quatf(orientation[1], orientation[2], orientation[3], orientation[0])) - - def __resolve_scale(self, prim: Usd.Prim) -> wp.vec3f: - scale = isaaclab_sim.resolve_prim_scale(prim) - return wp.vec3f(scale) - - def __resolve_shape_size(self, shape_type: SensorTiledCamera.RenderShapeType, prim: Usd.Prim) -> wp.vec3f: - if shape_type == SensorTiledCamera.RenderShapeType.SPHERE: - return self.__resolve_shape_size_sphere(prim) - if shape_type == SensorTiledCamera.RenderShapeType.CAPSULE: - return self.__resolve_shape_size_capsule(prim) - if shape_type == SensorTiledCamera.RenderShapeType.BOX: - return self.__resolve_shape_size_box(prim) - if shape_type == SensorTiledCamera.RenderShapeType.CYLINDER: - return self.__resolve_shape_size_cylinder(prim) - if shape_type == SensorTiledCamera.RenderShapeType.CONE: - return self.__resolve_shape_size_cone(prim) - if shape_type == SensorTiledCamera.RenderShapeType.PLANE: - return self.__resolve_shape_size_plane(prim) - return self.__resolve_scale(prim) - - def __resolve_shape_size_sphere(self, prim: Usd.Prim) -> wp.vec3f: - sphere = UsdGeom.Sphere(prim) - radius = sphere.GetRadiusAttr().Get() - return wp.vec3f(radius, 0.0, 0.0) - - def __resolve_shape_size_capsule(self, prim: Usd.Prim) -> wp.vec3f: - capsule = UsdGeom.Capsule(prim) - radius = capsule.GetRadiusAttr().Get() - height = capsule.GetHeightAttr().Get() - return wp.vec3f(radius, height, 0.0) - - def __resolve_shape_size_box(self, prim: Usd.Prim) -> wp.vec3f: - cube = UsdGeom.Cube(prim) - size = cube.GetSizeAttr().Get() - scale = self.__resolve_scale(prim) - return wp.vec3f(size * scale[0], size * scale[1], size * scale[2]) - - def __resolve_shape_size_cylinder(self, prim: Usd.Prim) -> wp.vec3f: - cylinder = UsdGeom.Cylinder(prim) - radius = cylinder.GetRadiusAttr().Get() - height = cylinder.GetHeightAttr().Get() - return wp.vec3f(radius, height, 0.0) - - def __resolve_shape_size_cone(self, prim: Usd.Prim) -> wp.vec3f: - cone = UsdGeom.Cone(prim) - radius = cone.GetRadiusAttr().Get() - height = cone.GetHeightAttr().Get() - return wp.vec3f(radius, height, 0.0) - - def __resolve_shape_size_plane(self, prim: Usd.Prim) -> wp.vec3f: - return wp.vec3f(0.0) diff --git a/source/isaaclab_tasks/test/benchmarking/configs_custom_reward_thresholds.yaml b/source/isaaclab_tasks/test/benchmarking/configs_custom_reward_thresholds.yaml deleted file mode 100644 index abe28337b3a..00000000000 --- a/source/isaaclab_tasks/test/benchmarking/configs_custom_reward_thresholds.yaml +++ /dev/null @@ -1,14 +0,0 @@ -# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). -# All rights reserved. -# -# SPDX-License-Identifier: BSD-3-Clause - -custom_rewards: - rl_games:Isaac-Dexsuite-Kuka-Allegro-Lift-v0: - max_iterations: 2000 - upper_thresholds: - duration: 999999 - sb3:Isaac-Lift-Cube-Franka-v0: - max_iterations: 200 - upper_thresholds: - duration: 999999