diff --git a/apps/isaaclab.python.kit b/apps/isaaclab.python.kit index de4252f2995..dbf93553c2d 100644 --- a/apps/isaaclab.python.kit +++ b/apps/isaaclab.python.kit @@ -17,7 +17,7 @@ keywords = ["experience", "app", "usd"] "isaacsim.core.api" = {} "isaacsim.core.cloner" = {} "isaacsim.core.nodes" = {} -"isaacsim.core.simulation_manager" = {} +# "isaacsim.core.simulation_manager" = {} # Replaced by isaaclab.sim.simulation_manager "isaacsim.core.throttling" = {} "isaacsim.core.utils" = {} "isaacsim.core.version" = {} diff --git a/apps/isaacsim_4_5/isaaclab.python.kit b/apps/isaacsim_4_5/isaaclab.python.kit index 89db9ffb0d6..101be98e738 100644 --- a/apps/isaacsim_4_5/isaaclab.python.kit +++ b/apps/isaacsim_4_5/isaaclab.python.kit @@ -17,7 +17,7 @@ keywords = ["experience", "app", "usd"] "isaacsim.core.api" = {} "isaacsim.core.cloner" = {} "isaacsim.core.nodes" = {} -"isaacsim.core.simulation_manager" = {} +# "isaacsim.core.simulation_manager" = {} # Replaced by isaaclab.sim.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..cbffce377e8 100644 --- a/docs/source/how-to/optimize_stage_creation.rst +++ b/docs/source/how-to/optimize_stage_creation.rst @@ -60,7 +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() + stage_in_memory = sim.stage with stage_utils.use_stage(stage_in_memory): # create cartpole scene scene_cfg = CartpoleSceneCfg(num_envs=1024) diff --git a/scripts/benchmarks/benchmark_cameras.py b/scripts/benchmarks/benchmark_cameras.py index 15d4284308e..e87a8f74e7b 100644 --- a/scripts/benchmarks/benchmark_cameras.py +++ b/scripts/benchmarks/benchmark_cameras.py @@ -509,7 +509,7 @@ def inject_cameras_into_task( """Loads the task, sticks cameras into the config, and creates the environment.""" cfg = load_cfg_from_registry(task, "env_cfg_entry_point") cfg.sim.device = args_cli.device - cfg.sim.use_fabric = args_cli.use_fabric + cfg.sim.physics_manager_cfg.use_fabric = args_cli.use_fabric scene_cfg = cfg.scene num_envs = int(num_cams / num_cameras_per_env) @@ -754,7 +754,7 @@ def main(): sim_cfg = sim_utils.SimulationCfg(device=args_cli.device) 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]) + sim._visualizer_interface.set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0]) scene_entities = design_scene( num_tiled_cams=args_cli.num_tiled_cameras, num_standard_cams=args_cli.num_standard_cameras, diff --git a/scripts/benchmarks/benchmark_load_robot.py b/scripts/benchmarks/benchmark_load_robot.py index 45d066162c8..8555bfda0b4 100644 --- a/scripts/benchmarks/benchmark_load_robot.py +++ b/scripts/benchmarks/benchmark_load_robot.py @@ -146,7 +146,7 @@ def main(): sim_cfg = sim_utils.SimulationCfg(device="cuda:0") sim = SimulationContext(sim_cfg) # Set main camera - sim.set_camera_view([2.5, 0.0, 4.0], [0.0, 0.0, 2.0]) + sim._visualizer_interface.set_camera_view([2.5, 0.0, 4.0], [0.0, 0.0, 2.0]) # Start the timer for creating the scene setup_time_begin = time.perf_counter_ns() diff --git a/scripts/benchmarks/benchmark_view_comparison.py b/scripts/benchmarks/benchmark_view_comparison.py index 6775a40d070..fbfa310f088 100644 --- a/scripts/benchmarks/benchmark_view_comparison.py +++ b/scripts/benchmarks/benchmark_view_comparison.py @@ -67,8 +67,7 @@ import time import torch -from isaacsim.core.simulation_manager import SimulationManager - +from isaaclab.physics.physx_manager import PhysxManager import isaaclab.sim as sim_utils import isaaclab.utils.math as math_utils from isaaclab.sim.views import XformPrimView @@ -129,7 +128,7 @@ def benchmark_view(view_type: str, num_iterations: int) -> tuple[dict[str, float num_prims = view.count view_name = "XformPrimView" else: # physx - physics_sim_view = SimulationManager.get_physics_sim_view() + physics_sim_view = PhysxManager.get_physics_sim_view() view = physics_sim_view.create_rigid_body_view(pattern) num_prims = view.count view_name = "PhysX RigidBodyView" @@ -181,8 +180,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 e4fd4c95d5b..596aed8e106 100644 --- a/scripts/benchmarks/benchmark_xform_prim_view.py +++ b/scripts/benchmarks/benchmark_xform_prim_view.py @@ -215,8 +215,6 @@ def benchmark_xform_prim_view( timing_results["get_both"] = (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/scripts/demos/arms.py b/scripts/demos/arms.py index 92bd4499d6d..81e1f323032 100644 --- a/scripts/demos/arms.py +++ b/scripts/demos/arms.py @@ -212,7 +212,7 @@ def main(): sim_cfg = sim_utils.SimulationCfg(device=args_cli.device) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera - sim.set_camera_view([3.5, 0.0, 3.2], [0.0, 0.0, 0.5]) + sim._visualizer_interface.set_camera_view([3.5, 0.0, 3.2], [0.0, 0.0, 0.5]) # design scene scene_entities, scene_origins = design_scene() scene_origins = torch.tensor(scene_origins, device=sim.device) diff --git a/scripts/demos/bin_packing.py b/scripts/demos/bin_packing.py index 192026c81d9..fcb100ceec7 100644 --- a/scripts/demos/bin_packing.py +++ b/scripts/demos/bin_packing.py @@ -331,7 +331,7 @@ def main() -> None: sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device) sim = SimulationContext(sim_cfg) # Set main camera - sim.set_camera_view((2.5, 0.0, 4.0), (0.0, 0.0, 2.0)) + sim._visualizer_interface.set_camera_view((2.5, 0.0, 4.0), (0.0, 0.0, 2.0)) # Design scene scene_cfg = MultiObjectSceneCfg(num_envs=args_cli.num_envs, env_spacing=1.0, replicate_physics=False) diff --git a/scripts/demos/bipeds.py b/scripts/demos/bipeds.py index 1da3677cb5b..6ed349bd527 100644 --- a/scripts/demos/bipeds.py +++ b/scripts/demos/bipeds.py @@ -115,7 +115,7 @@ def main(): sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device) 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]) + sim._visualizer_interface.set_camera_view(eye=[3.0, 0.0, 2.25], target=[0.0, 0.0, 1.0]) # design scene robots, origins = design_scene(sim) diff --git a/scripts/demos/deformables.py b/scripts/demos/deformables.py index bebaa51a4e8..8e3e589fe9a 100644 --- a/scripts/demos/deformables.py +++ b/scripts/demos/deformables.py @@ -180,7 +180,7 @@ def main(): sim_cfg = sim_utils.SimulationCfg(dt=0.01, device=args_cli.device) 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]) + sim._visualizer_interface.set_camera_view([4.0, 4.0, 3.0], [0.5, 0.5, 0.0]) # Design scene by adding assets to it scene_entities, scene_origins = design_scene() diff --git a/scripts/demos/hands.py b/scripts/demos/hands.py index a0fa04e0fbf..c9f8f3bf513 100644 --- a/scripts/demos/hands.py +++ b/scripts/demos/hands.py @@ -146,7 +146,7 @@ def main(): sim_cfg = sim_utils.SimulationCfg(dt=0.01, device=args_cli.device) 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]) + sim._visualizer_interface.set_camera_view(eye=[0.0, -0.5, 1.5], target=[0.0, -0.2, 0.5]) # design scene scene_entities, scene_origins = design_scene() scene_origins = torch.tensor(scene_origins, device=sim.device) diff --git a/scripts/demos/haply_teleoperation.py b/scripts/demos/haply_teleoperation.py index b6d02900baf..d3d9846e1ae 100644 --- a/scripts/demos/haply_teleoperation.py +++ b/scripts/demos/haply_teleoperation.py @@ -336,7 +336,7 @@ def main(): sim = sim_utils.SimulationContext(sim_cfg) # set the simulation view - sim.set_camera_view([1.6, 1.0, 1.70], [0.4, 0.0, 1.0]) + sim._visualizer_interface.set_camera_view([1.6, 1.0, 1.70], [0.4, 0.0, 1.0]) scene_cfg = FrankaHaplySceneCfg(num_envs=args_cli.num_envs, env_spacing=2.0) scene = InteractiveScene(scene_cfg) diff --git a/scripts/demos/markers.py b/scripts/demos/markers.py index 6152dcf5226..042ceed5bdd 100644 --- a/scripts/demos/markers.py +++ b/scripts/demos/markers.py @@ -97,7 +97,7 @@ def main(): sim_cfg = sim_utils.SimulationCfg(dt=0.01, device=args_cli.device) sim = SimulationContext(sim_cfg) # Set main camera - sim.set_camera_view([0.0, 18.0, 12.0], [0.0, 3.0, 0.0]) + sim._visualizer_interface.set_camera_view([0.0, 18.0, 12.0], [0.0, 3.0, 0.0]) # Spawn things into stage # Lights diff --git a/scripts/demos/multi_asset.py b/scripts/demos/multi_asset.py index d104eb161d3..a5aab0488e9 100644 --- a/scripts/demos/multi_asset.py +++ b/scripts/demos/multi_asset.py @@ -278,7 +278,7 @@ def main(): sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device) sim = SimulationContext(sim_cfg) # Set main camera - sim.set_camera_view([2.5, 0.0, 4.0], [0.0, 0.0, 2.0]) + sim._visualizer_interface.set_camera_view([2.5, 0.0, 4.0], [0.0, 0.0, 2.0]) # Design scene scene_cfg = MultiObjectSceneCfg(num_envs=args_cli.num_envs, env_spacing=2.0, replicate_physics=False) diff --git a/scripts/demos/procedural_terrain.py b/scripts/demos/procedural_terrain.py index e409ee4f091..0fe30d7cc28 100644 --- a/scripts/demos/procedural_terrain.py +++ b/scripts/demos/procedural_terrain.py @@ -156,7 +156,7 @@ def main(): sim_cfg = sim_utils.SimulationCfg(dt=0.01, device=args_cli.device) 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]) + sim._visualizer_interface.set_camera_view(eye=[5.0, 5.0, 5.0], target=[0.0, 0.0, 0.0]) # design scene scene_entities, scene_origins = design_scene() # Play the simulator diff --git a/scripts/demos/quadcopter.py b/scripts/demos/quadcopter.py index 2296245d510..a7f4852a495 100644 --- a/scripts/demos/quadcopter.py +++ b/scripts/demos/quadcopter.py @@ -50,7 +50,7 @@ def main(): sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device) 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]) + sim._visualizer_interface.set_camera_view(eye=[0.5, 0.5, 1.0], target=[0.0, 0.0, 0.5]) # Spawn things into stage # Ground-plane @@ -73,7 +73,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_physx_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..a19070713ce 100644 --- a/scripts/demos/quadrupeds.py +++ b/scripts/demos/quadrupeds.py @@ -172,7 +172,7 @@ def main(): # Initialize the simulation context sim = sim_utils.SimulationContext(sim_utils.SimulationCfg(dt=0.01)) # Set main camera - sim.set_camera_view(eye=[2.5, 2.5, 2.5], target=[0.0, 0.0, 0.0]) + sim._visualizer_interface.set_camera_view(eye=[2.5, 2.5, 2.5], target=[0.0, 0.0, 0.0]) # design scene scene_entities, scene_origins = design_scene() scene_origins = torch.tensor(scene_origins, device=sim.device) diff --git a/scripts/demos/sensors/cameras.py b/scripts/demos/sensors/cameras.py index 5c1effcc214..e5db9fadc20 100644 --- a/scripts/demos/sensors/cameras.py +++ b/scripts/demos/sensors/cameras.py @@ -282,7 +282,7 @@ def main(): sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device, 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]) + sim._visualizer_interface.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) # design scene scene_cfg = SensorsSceneCfg(num_envs=args_cli.num_envs, env_spacing=2.0) scene = InteractiveScene(scene_cfg) diff --git a/scripts/demos/sensors/contact_sensor.py b/scripts/demos/sensors/contact_sensor.py index 547d7b2b1b0..6110caa9f95 100644 --- a/scripts/demos/sensors/contact_sensor.py +++ b/scripts/demos/sensors/contact_sensor.py @@ -158,7 +158,7 @@ def main(): sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device) 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]) + sim._visualizer_interface.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) # design scene scene_cfg = ContactSensorSceneCfg(num_envs=args_cli.num_envs, env_spacing=2.0) scene = InteractiveScene(scene_cfg) diff --git a/scripts/demos/sensors/frame_transformer_sensor.py b/scripts/demos/sensors/frame_transformer_sensor.py index c20bc23afdb..7a3d8857c21 100644 --- a/scripts/demos/sensors/frame_transformer_sensor.py +++ b/scripts/demos/sensors/frame_transformer_sensor.py @@ -152,7 +152,7 @@ def main(): sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device) 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]) + sim._visualizer_interface.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) # design scene scene_cfg = FrameTransformerSensorSceneCfg(num_envs=args_cli.num_envs, env_spacing=2.0) scene = InteractiveScene(scene_cfg) diff --git a/scripts/demos/sensors/imu_sensor.py b/scripts/demos/sensors/imu_sensor.py index e6a922c8455..ccd3e542212 100644 --- a/scripts/demos/sensors/imu_sensor.py +++ b/scripts/demos/sensors/imu_sensor.py @@ -125,7 +125,7 @@ def main(): sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device) 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]) + sim._visualizer_interface.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) # design scene scene_cfg = ImuSensorSceneCfg(num_envs=args_cli.num_envs, env_spacing=2.0) scene = InteractiveScene(scene_cfg) diff --git a/scripts/demos/sensors/multi_mesh_raycaster.py b/scripts/demos/sensors/multi_mesh_raycaster.py index 8868ad20861..7af4bd3e7b8 100644 --- a/scripts/demos/sensors/multi_mesh_raycaster.py +++ b/scripts/demos/sensors/multi_mesh_raycaster.py @@ -280,7 +280,7 @@ def main(): sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device) 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]) + sim._visualizer_interface.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) # design scene scene_cfg = RaycasterSensorSceneCfg(num_envs=args_cli.num_envs, env_spacing=2.0, replicate_physics=False) scene = InteractiveScene(scene_cfg) diff --git a/scripts/demos/sensors/multi_mesh_raycaster_camera.py b/scripts/demos/sensors/multi_mesh_raycaster_camera.py index 1f676f3f0b0..475ca228583 100644 --- a/scripts/demos/sensors/multi_mesh_raycaster_camera.py +++ b/scripts/demos/sensors/multi_mesh_raycaster_camera.py @@ -306,7 +306,7 @@ def main(): sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device) 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]) + sim._visualizer_interface.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) # design scene scene_cfg = RaycasterSensorSceneCfg(num_envs=args_cli.num_envs, env_spacing=2.0, replicate_physics=False) scene = InteractiveScene(scene_cfg) diff --git a/scripts/demos/sensors/raycaster_sensor.py b/scripts/demos/sensors/raycaster_sensor.py index 302fff8ddf5..bf6ad65380c 100644 --- a/scripts/demos/sensors/raycaster_sensor.py +++ b/scripts/demos/sensors/raycaster_sensor.py @@ -143,7 +143,7 @@ def main(): sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device) 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]) + sim._visualizer_interface.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) # design scene scene_cfg = RaycasterSensorSceneCfg(num_envs=args_cli.num_envs, env_spacing=2.0) scene = InteractiveScene(scene_cfg) diff --git a/scripts/environments/state_machine/lift_cube_sm.py b/scripts/environments/state_machine/lift_cube_sm.py index 21338f74ed6..7d1b6d91880 100644 --- a/scripts/environments/state_machine/lift_cube_sm.py +++ b/scripts/environments/state_machine/lift_cube_sm.py @@ -276,7 +276,7 @@ def main(): desired_orientation[:, 1] = 1.0 # create state machine pick_sm = PickAndLiftSm( - env_cfg.sim.dt * env_cfg.decimation, env.unwrapped.num_envs, env.unwrapped.device, position_threshold=0.01 + env_cfg.sim.physics_manager_cfg.dt * env_cfg.decimation, env.unwrapped.num_envs, env.unwrapped.device, position_threshold=0.01 ) while simulation_app.is_running(): diff --git a/scripts/environments/state_machine/lift_teddy_bear.py b/scripts/environments/state_machine/lift_teddy_bear.py index ad4e560fa65..372ae185c32 100644 --- a/scripts/environments/state_machine/lift_teddy_bear.py +++ b/scripts/environments/state_machine/lift_teddy_bear.py @@ -297,7 +297,7 @@ def main(): object_local_grasp_position = torch.tensor([0.02, -0.08, 0.0], device=env.unwrapped.device) # create state machine - pick_sm = PickAndLiftSm(env_cfg.sim.dt * env_cfg.decimation, env.unwrapped.num_envs, env.unwrapped.device) + pick_sm = PickAndLiftSm(env_cfg.sim.physics_manager_cfg.dt * env_cfg.decimation, env.unwrapped.num_envs, env.unwrapped.device) while simulation_app.is_running(): # run everything in inference mode diff --git a/scripts/environments/state_machine/open_cabinet_sm.py b/scripts/environments/state_machine/open_cabinet_sm.py index 94c8d4d832e..b3e2b6858e9 100644 --- a/scripts/environments/state_machine/open_cabinet_sm.py +++ b/scripts/environments/state_machine/open_cabinet_sm.py @@ -293,7 +293,7 @@ def main(): desired_orientation = torch.zeros((env.unwrapped.num_envs, 4), device=env.unwrapped.device) desired_orientation[:, 1] = 1.0 # create state machine - open_sm = OpenDrawerSm(env_cfg.sim.dt * env_cfg.decimation, env.unwrapped.num_envs, env.unwrapped.device) + open_sm = OpenDrawerSm(env_cfg.sim.physics_manager_cfg.dt * env_cfg.decimation, env.unwrapped.num_envs, env.unwrapped.device) while simulation_app.is_running(): # run everything in inference mode diff --git a/scripts/tools/check_instanceable.py b/scripts/tools/check_instanceable.py index fedb771f611..c4a43de487f 100644 --- a/scripts/tools/check_instanceable.py +++ b/scripts/tools/check_instanceable.py @@ -64,7 +64,7 @@ """Rest everything follows.""" -from isaacsim.core.api.simulation_context import SimulationContext +from isaaclab.sim import SimulationContext from isaacsim.core.cloner import GridCloner import isaaclab.sim as sim_utils diff --git a/scripts/tutorials/00_sim/create_empty.py b/scripts/tutorials/00_sim/create_empty.py index 6fa283a68f1..51506800c12 100644 --- a/scripts/tutorials/00_sim/create_empty.py +++ b/scripts/tutorials/00_sim/create_empty.py @@ -41,7 +41,7 @@ def main(): sim_cfg = SimulationCfg(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]) + sim._visualizer_interface.set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0]) # Play the simulator sim.reset() diff --git a/scripts/tutorials/00_sim/launch_app.py b/scripts/tutorials/00_sim/launch_app.py index 1622d3ba956..9e2f77b9e68 100644 --- a/scripts/tutorials/00_sim/launch_app.py +++ b/scripts/tutorials/00_sim/launch_app.py @@ -73,7 +73,7 @@ def main(): sim_cfg = sim_utils.SimulationCfg(dt=0.01, device=args_cli.device) 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]) + sim._visualizer_interface.set_camera_view([2.0, 0.0, 2.5], [-0.5, 0.0, 0.5]) # Design scene by adding assets to it design_scene() diff --git a/scripts/tutorials/00_sim/log_time.py b/scripts/tutorials/00_sim/log_time.py index 2e4445c3d47..4370107bba9 100644 --- a/scripts/tutorials/00_sim/log_time.py +++ b/scripts/tutorials/00_sim/log_time.py @@ -56,7 +56,7 @@ def main(): sim_cfg = SimulationCfg(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]) + sim._visualizer_interface.set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0]) # Play the simulator sim.reset() diff --git a/scripts/tutorials/00_sim/set_rendering_mode.py b/scripts/tutorials/00_sim/set_rendering_mode.py index 220b5b765be..00244b893a8 100644 --- a/scripts/tutorials/00_sim/set_rendering_mode.py +++ b/scripts/tutorials/00_sim/set_rendering_mode.py @@ -58,7 +58,7 @@ def main(): sim = sim_utils.SimulationContext(sim_cfg) # Pose camera in the hospital lobby area - sim.set_camera_view([-11, -0.5, 2], [0, 0, 0.5]) + sim._visualizer_interface.set_camera_view([-11, -0.5, 2], [0, 0, 0.5]) # Load hospital scene hospital_usd_path = f"{ISAAC_NUCLEUS_DIR}/Environments/Hospital/hospital.usd" diff --git a/scripts/tutorials/00_sim/spawn_prims.py b/scripts/tutorials/00_sim/spawn_prims.py index 7c120bd308d..73b224a59c0 100644 --- a/scripts/tutorials/00_sim/spawn_prims.py +++ b/scripts/tutorials/00_sim/spawn_prims.py @@ -93,7 +93,7 @@ def main(): sim_cfg = sim_utils.SimulationCfg(dt=0.01, device=args_cli.device) 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]) + sim._visualizer_interface.set_camera_view([2.0, 0.0, 2.5], [-0.5, 0.0, 0.5]) # Design scene design_scene() # Play the simulator diff --git a/scripts/tutorials/01_assets/add_new_robot.py b/scripts/tutorials/01_assets/add_new_robot.py index bc322d10947..fa1ccfda96b 100644 --- a/scripts/tutorials/01_assets/add_new_robot.py +++ b/scripts/tutorials/01_assets/add_new_robot.py @@ -162,7 +162,7 @@ def main(): # Initialize the simulation context sim_cfg = sim_utils.SimulationCfg(device=args_cli.device) sim = sim_utils.SimulationContext(sim_cfg) - sim.set_camera_view([3.5, 0.0, 3.2], [0.0, 0.0, 0.5]) + sim._visualizer_interface.set_camera_view([3.5, 0.0, 3.2], [0.0, 0.0, 0.5]) # Design scene scene_cfg = NewRobotsSceneCfg(args_cli.num_envs, env_spacing=2.0) scene = InteractiveScene(scene_cfg) diff --git a/scripts/tutorials/01_assets/run_articulation.py b/scripts/tutorials/01_assets/run_articulation.py index bc4254cbae1..d5ea801e536 100644 --- a/scripts/tutorials/01_assets/run_articulation.py +++ b/scripts/tutorials/01_assets/run_articulation.py @@ -122,7 +122,7 @@ def main(): sim_cfg = sim_utils.SimulationCfg(device=args_cli.device) sim = SimulationContext(sim_cfg) # Set main camera - sim.set_camera_view([2.5, 0.0, 4.0], [0.0, 0.0, 2.0]) + sim._visualizer_interface.set_camera_view([2.5, 0.0, 4.0], [0.0, 0.0, 2.0]) # Design scene scene_entities, scene_origins = design_scene() scene_origins = torch.tensor(scene_origins, device=sim.device) diff --git a/scripts/tutorials/01_assets/run_deformable_object.py b/scripts/tutorials/01_assets/run_deformable_object.py index 3623bb3d8a1..2eaac68b89a 100644 --- a/scripts/tutorials/01_assets/run_deformable_object.py +++ b/scripts/tutorials/01_assets/run_deformable_object.py @@ -147,7 +147,7 @@ def main(): sim_cfg = sim_utils.SimulationCfg(device=args_cli.device) sim = SimulationContext(sim_cfg) # Set main camera - sim.set_camera_view(eye=[3.0, 0.0, 1.0], target=[0.0, 0.0, 0.5]) + sim._visualizer_interface.set_camera_view(eye=[3.0, 0.0, 1.0], target=[0.0, 0.0, 0.5]) # Design scene scene_entities, scene_origins = design_scene() scene_origins = torch.tensor(scene_origins, device=sim.device) diff --git a/scripts/tutorials/01_assets/run_rigid_object.py b/scripts/tutorials/01_assets/run_rigid_object.py index dc1a88c57eb..fc10a595b7b 100644 --- a/scripts/tutorials/01_assets/run_rigid_object.py +++ b/scripts/tutorials/01_assets/run_rigid_object.py @@ -127,7 +127,7 @@ def main(): sim_cfg = sim_utils.SimulationCfg(device=args_cli.device) sim = SimulationContext(sim_cfg) # Set main camera - sim.set_camera_view(eye=[1.5, 0.0, 1.0], target=[0.0, 0.0, 0.0]) + sim._visualizer_interface.set_camera_view(eye=[1.5, 0.0, 1.0], target=[0.0, 0.0, 0.0]) # Design scene scene_entities, scene_origins = design_scene() scene_origins = torch.tensor(scene_origins, device=sim.device) diff --git a/scripts/tutorials/01_assets/run_surface_gripper.py b/scripts/tutorials/01_assets/run_surface_gripper.py index 066dd9a077d..6a2c2d0970e 100644 --- a/scripts/tutorials/01_assets/run_surface_gripper.py +++ b/scripts/tutorials/01_assets/run_surface_gripper.py @@ -162,7 +162,7 @@ def main(): sim_cfg = sim_utils.SimulationCfg(device=args_cli.device) sim = SimulationContext(sim_cfg) # Set main camera - sim.set_camera_view([2.75, 7.5, 10.0], [2.75, 0.0, 0.0]) + sim._visualizer_interface.set_camera_view([2.75, 7.5, 10.0], [2.75, 0.0, 0.0]) # Design scene scene_entities, scene_origins = design_scene() scene_origins = torch.tensor(scene_origins, device=sim.device) diff --git a/scripts/tutorials/02_scene/create_scene.py b/scripts/tutorials/02_scene/create_scene.py index 82b5b21c009..8e056f8cf80 100644 --- a/scripts/tutorials/02_scene/create_scene.py +++ b/scripts/tutorials/02_scene/create_scene.py @@ -113,7 +113,7 @@ def main(): sim_cfg = sim_utils.SimulationCfg(device=args_cli.device) sim = SimulationContext(sim_cfg) # Set main camera - sim.set_camera_view([2.5, 0.0, 4.0], [0.0, 0.0, 2.0]) + sim._visualizer_interface.set_camera_view([2.5, 0.0, 4.0], [0.0, 0.0, 2.0]) # Design scene scene_cfg = CartpoleSceneCfg(num_envs=args_cli.num_envs, env_spacing=2.0) scene = InteractiveScene(scene_cfg) diff --git a/scripts/tutorials/03_envs/create_cartpole_base_env.py b/scripts/tutorials/03_envs/create_cartpole_base_env.py index cbaf2b07086..53f0dd2ce86 100644 --- a/scripts/tutorials/03_envs/create_cartpole_base_env.py +++ b/scripts/tutorials/03_envs/create_cartpole_base_env.py @@ -132,7 +132,7 @@ def __post_init__(self): # step settings self.decimation = 4 # env step every 4 sim steps: 200Hz / 4 = 50Hz # simulation settings - self.sim.dt = 0.005 # sim step every 5ms: 200Hz + self.sim.physics_manager_cfg.dt = 0.005 # sim step every 5ms: 200Hz def main(): diff --git a/scripts/tutorials/03_envs/create_cube_base_env.py b/scripts/tutorials/03_envs/create_cube_base_env.py index 09ee7fac30f..cb227de2ecf 100644 --- a/scripts/tutorials/03_envs/create_cube_base_env.py +++ b/scripts/tutorials/03_envs/create_cube_base_env.py @@ -301,7 +301,7 @@ def __post_init__(self): # general settings self.decimation = 2 # simulation settings - self.sim.dt = 0.01 + self.sim.physics_manager_cfg.dt = 0.01 self.sim.physics_material = self.scene.terrain.physics_material self.sim.render_interval = 2 # render interval should be a multiple of decimation self.sim.device = args_cli.device diff --git a/scripts/tutorials/03_envs/create_quadruped_base_env.py b/scripts/tutorials/03_envs/create_quadruped_base_env.py index 78f5b75ec5f..90d4934adab 100644 --- a/scripts/tutorials/03_envs/create_quadruped_base_env.py +++ b/scripts/tutorials/03_envs/create_quadruped_base_env.py @@ -192,13 +192,13 @@ def __post_init__(self): # general settings self.decimation = 4 # env decimation -> 50 Hz control # simulation settings - self.sim.dt = 0.005 # simulation timestep -> 200 Hz physics + self.sim.physics_manager_cfg.dt = 0.005 # simulation timestep -> 200 Hz physics self.sim.physics_material = self.scene.terrain.physics_material self.sim.device = args_cli.device # 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 # 50 Hz + self.scene.height_scanner.update_period = self.decimation * self.sim.physics_manager_cfg.dt # 50 Hz def main(): diff --git a/scripts/tutorials/03_envs/policy_inference_in_usd.py b/scripts/tutorials/03_envs/policy_inference_in_usd.py index 4cf9723932f..ee178ef0a18 100644 --- a/scripts/tutorials/03_envs/policy_inference_in_usd.py +++ b/scripts/tutorials/03_envs/policy_inference_in_usd.py @@ -69,7 +69,7 @@ def main(): ) env_cfg.sim.device = args_cli.device if args_cli.device == "cpu": - env_cfg.sim.use_fabric = False + env_cfg.sim.physics_manager_cfg.use_fabric = False # create environment env = ManagerBasedRLEnv(cfg=env_cfg) diff --git a/scripts/tutorials/04_sensors/add_sensors_on_robot.py b/scripts/tutorials/04_sensors/add_sensors_on_robot.py index 5cc6de6778b..4b57489fc20 100644 --- a/scripts/tutorials/04_sensors/add_sensors_on_robot.py +++ b/scripts/tutorials/04_sensors/add_sensors_on_robot.py @@ -160,7 +160,7 @@ def main(): sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device) 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]) + sim._visualizer_interface.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) # Design scene scene_cfg = SensorsSceneCfg(num_envs=args_cli.num_envs, env_spacing=2.0) scene = InteractiveScene(scene_cfg) diff --git a/scripts/tutorials/04_sensors/run_frame_transformer.py b/scripts/tutorials/04_sensors/run_frame_transformer.py index 8f951e93639..a8a24e095f7 100644 --- a/scripts/tutorials/04_sensors/run_frame_transformer.py +++ b/scripts/tutorials/04_sensors/run_frame_transformer.py @@ -167,7 +167,7 @@ def main(): sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device) 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]) + sim._visualizer_interface.set_camera_view(eye=[2.5, 2.5, 2.5], target=[0.0, 0.0, 0.0]) # Design scene scene_entities = design_scene() # Play the simulator diff --git a/scripts/tutorials/04_sensors/run_ray_caster.py b/scripts/tutorials/04_sensors/run_ray_caster.py index 51780accbdd..a62ed0b596a 100644 --- a/scripts/tutorials/04_sensors/run_ray_caster.py +++ b/scripts/tutorials/04_sensors/run_ray_caster.py @@ -131,7 +131,7 @@ def main(): sim_cfg = sim_utils.SimulationCfg(device=args_cli.device) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera - sim.set_camera_view([0.0, 15.0, 15.0], [0.0, 0.0, -2.5]) + sim._visualizer_interface.set_camera_view([0.0, 15.0, 15.0], [0.0, 0.0, -2.5]) # Design scene scene_entities = design_scene() # Play simulator diff --git a/scripts/tutorials/04_sensors/run_ray_caster_camera.py b/scripts/tutorials/04_sensors/run_ray_caster_camera.py index d9979965a0b..d210c66a77d 100644 --- a/scripts/tutorials/04_sensors/run_ray_caster_camera.py +++ b/scripts/tutorials/04_sensors/run_ray_caster_camera.py @@ -165,7 +165,7 @@ def main(): sim_cfg = sim_utils.SimulationCfg() sim = sim_utils.SimulationContext(sim_cfg) # Set main camera - sim.set_camera_view([2.5, 2.5, 3.5], [0.0, 0.0, 0.0]) + sim._visualizer_interface.set_camera_view([2.5, 2.5, 3.5], [0.0, 0.0, 0.0]) # Design scene scene_entities = design_scene() # Play simulator diff --git a/scripts/tutorials/04_sensors/run_usd_camera.py b/scripts/tutorials/04_sensors/run_usd_camera.py index 0b953db0d17..ffc36a8c9ba 100644 --- a/scripts/tutorials/04_sensors/run_usd_camera.py +++ b/scripts/tutorials/04_sensors/run_usd_camera.py @@ -195,7 +195,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) @@ -247,7 +247,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], @@ -270,7 +270,7 @@ def main(): sim_cfg = sim_utils.SimulationCfg(device=args_cli.device) 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]) + sim._visualizer_interface.set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0]) # Design scene scene_entities = design_scene() # Play simulator diff --git a/scripts/tutorials/05_controllers/run_diff_ik.py b/scripts/tutorials/05_controllers/run_diff_ik.py index 22d17963235..01d6fad8e76 100644 --- a/scripts/tutorials/05_controllers/run_diff_ik.py +++ b/scripts/tutorials/05_controllers/run_diff_ik.py @@ -193,7 +193,7 @@ def main(): sim_cfg = sim_utils.SimulationCfg(dt=0.01, device=args_cli.device) 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]) + sim._visualizer_interface.set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0]) # Design scene scene_cfg = TableTopSceneCfg(num_envs=args_cli.num_envs, env_spacing=2.0) scene = InteractiveScene(scene_cfg) diff --git a/scripts/tutorials/05_controllers/run_osc.py b/scripts/tutorials/05_controllers/run_osc.py index 98b2532a0a2..b3e329a6e85 100644 --- a/scripts/tutorials/05_controllers/run_osc.py +++ b/scripts/tutorials/05_controllers/run_osc.py @@ -465,7 +465,7 @@ def main(): sim_cfg = sim_utils.SimulationCfg(dt=0.01, device=args_cli.device) 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]) + sim._visualizer_interface.set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0]) # Design scene scene_cfg = SceneCfg(num_envs=args_cli.num_envs, env_spacing=2.0) scene = InteractiveScene(scene_cfg) diff --git a/source/isaaclab/isaaclab/assets/articulation/articulation.py b/source/isaaclab/isaaclab/assets/articulation/articulation.py index 552e9b2d92e..f4da9e3b3ad 100644 --- a/source/isaaclab/isaaclab/assets/articulation/articulation.py +++ b/source/isaaclab/isaaclab/assets/articulation/articulation.py @@ -15,7 +15,7 @@ from typing import TYPE_CHECKING import omni.physics.tensors.impl.api as physx -from isaacsim.core.simulation_manager import SimulationManager +from isaaclab.physics.physx_manager import PhysxManager from pxr import PhysxSchema, UsdPhysics import isaaclab.sim as sim_utils @@ -1475,7 +1475,7 @@ def write_spatial_tendon_properties_to_sim( def _initialize_impl(self): # obtain global simulation view - self._physics_sim_view = SimulationManager.get_physics_sim_view() + self._physics_sim_view = PhysxManager.get_physics_sim_view() if self.cfg.articulation_root_prim_path is not None: # The articulation root prim path is specified explicitly, so we can just use this. diff --git a/source/isaaclab/isaaclab/assets/articulation/articulation_data.py b/source/isaaclab/isaaclab/assets/articulation/articulation_data.py index f1ab1d05586..9707c15d192 100644 --- a/source/isaaclab/isaaclab/assets/articulation/articulation_data.py +++ b/source/isaaclab/isaaclab/assets/articulation/articulation_data.py @@ -8,7 +8,7 @@ import weakref import omni.physics.tensors.impl.api as physx -from isaacsim.core.simulation_manager import SimulationManager +from isaaclab.physics.physx_manager import PhysxManager import isaaclab.utils.math as math_utils from isaaclab.utils.buffers import TimestampedBuffer @@ -53,7 +53,7 @@ def __init__(self, root_physx_view: physx.ArticulationView, device: str): self._sim_timestamp = 0.0 # obtain global simulation view - self._physics_sim_view = SimulationManager.get_physics_sim_view() + self._physics_sim_view = PhysxManager.get_physics_sim_view() gravity = self._physics_sim_view.get_gravity() # Convert to direction vector gravity_dir = torch.tensor((gravity[0], gravity[1], gravity[2]), device=self.device) diff --git a/source/isaaclab/isaaclab/assets/asset_base.py b/source/isaaclab/isaaclab/assets/asset_base.py index 3c78c079377..eb0a634e8a3 100644 --- a/source/isaaclab/isaaclab/assets/asset_base.py +++ b/source/isaaclab/isaaclab/assets/asset_base.py @@ -16,7 +16,7 @@ import omni.kit.app import omni.timeline -from isaacsim.core.simulation_manager import IsaacEvents, SimulationManager +from isaaclab.sim import IsaacEvents, PhysxManager import isaaclab.sim as sim_utils from isaaclab.sim.utils.stage import get_current_stage @@ -295,7 +295,7 @@ def safe_callback(callback_name, event, obj_ref): order=10, ) # register prim deletion callback - self._prim_deletion_callback_id = SimulationManager.register_callback( + self._prim_deletion_callback_id = PhysxManager.register_callback( lambda event, obj_ref=obj_ref: safe_callback("_on_prim_deletion", event, obj_ref), event=IsaacEvents.PRIM_DELETION, ) @@ -308,15 +308,18 @@ def _initialize_callback(self, event): called whenever the simulator "plays" from a "stop" state. """ if not self._is_initialized: - # obtain simulation related information - self._backend = SimulationManager.get_backend() - self._device = SimulationManager.get_physics_sim_device() - # initialize the asset try: + # Obtain Simulation Context + sim = sim_utils.SimulationContext.instance() + if sim is None: + raise RuntimeError("Simulation Context is not initialized!") + # Obtain device and backend + self._device = sim.device + # initialize the asset self._initialize_impl() except Exception as e: - if builtins.ISAACLAB_CALLBACK_EXCEPTION is None: - builtins.ISAACLAB_CALLBACK_EXCEPTION = e + if builtins.ISAACLAB_CALLBACK_EXCEPTION is None: # type: ignore + builtins.ISAACLAB_CALLBACK_EXCEPTION = e # type: ignore # set flag self._is_initialized = True @@ -327,15 +330,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: This function is called when the prim is deleted. """ + prim_path = event.payload["prim_path"] if prim_path == "/": self._clear_callbacks() return @@ -345,10 +349,14 @@ def _on_prim_deletion(self, prim_path: str) -> None: if result: self._clear_callbacks() - def _clear_callbacks(self) -> None: - """Clears the callbacks.""" + 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._prim_deletion_callback_id: - SimulationManager.deregister_callback(self._prim_deletion_callback_id) + PhysxManager.deregister_callback(self._prim_deletion_callback_id) self._prim_deletion_callback_id = None if self._initialize_handle: self._initialize_handle.unsubscribe() diff --git a/source/isaaclab/isaaclab/assets/deformable_object/deformable_object.py b/source/isaaclab/isaaclab/assets/deformable_object/deformable_object.py index 1d2ecffb612..84a504ada14 100644 --- a/source/isaaclab/isaaclab/assets/deformable_object/deformable_object.py +++ b/source/isaaclab/isaaclab/assets/deformable_object/deformable_object.py @@ -11,7 +11,7 @@ from typing import TYPE_CHECKING import omni.physics.tensors.impl.api as physx -from isaacsim.core.simulation_manager import SimulationManager +from isaaclab.physics.physx_manager import PhysxManager from pxr import PhysxSchema, UsdShade import isaaclab.sim as sim_utils @@ -266,7 +266,7 @@ def transform_nodal_pos( def _initialize_impl(self): # obtain global simulation view - self._physics_sim_view = SimulationManager.get_physics_sim_view() + self._physics_sim_view = PhysxManager.get_physics_sim_view() # obtain the first prim in the regex expression (all others are assumed to be a copy of this) template_prim = sim_utils.find_first_matching_prim(self.cfg.prim_path) if template_prim is None: diff --git a/source/isaaclab/isaaclab/assets/rigid_object/rigid_object.py b/source/isaaclab/isaaclab/assets/rigid_object/rigid_object.py index 04a31ace553..e505f17ca29 100644 --- a/source/isaaclab/isaaclab/assets/rigid_object/rigid_object.py +++ b/source/isaaclab/isaaclab/assets/rigid_object/rigid_object.py @@ -11,7 +11,7 @@ from typing import TYPE_CHECKING import omni.physics.tensors.impl.api as physx -from isaacsim.core.simulation_manager import SimulationManager +from isaaclab.physics.physx_manager import PhysxManager from pxr import UsdPhysics import isaaclab.sim as sim_utils @@ -458,7 +458,7 @@ def set_external_force_and_torque( def _initialize_impl(self): # obtain global simulation view - self._physics_sim_view = SimulationManager.get_physics_sim_view() + self._physics_sim_view = PhysxManager.get_physics_sim_view() # obtain the first prim in the regex expression (all others are assumed to be a copy of this) template_prim = sim_utils.find_first_matching_prim(self.cfg.prim_path) if template_prim is None: diff --git a/source/isaaclab/isaaclab/assets/rigid_object_collection/rigid_object_collection.py b/source/isaaclab/isaaclab/assets/rigid_object_collection/rigid_object_collection.py index 0c9e24fba12..75d483276b1 100644 --- a/source/isaaclab/isaaclab/assets/rigid_object_collection/rigid_object_collection.py +++ b/source/isaaclab/isaaclab/assets/rigid_object_collection/rigid_object_collection.py @@ -12,7 +12,7 @@ from typing import TYPE_CHECKING import omni.physics.tensors.impl.api as physx -from isaacsim.core.simulation_manager import SimulationManager +from isaaclab.physics.physx_manager import PhysxManager from pxr import UsdPhysics import isaaclab.sim as sim_utils @@ -594,7 +594,7 @@ def _initialize_impl(self): # clear object names list to prevent double counting on re-initialization self._object_names_list.clear() # obtain global simulation view - self._physics_sim_view = SimulationManager.get_physics_sim_view() + self._physics_sim_view = PhysxManager.get_physics_sim_view() root_prim_path_exprs = [] for name, rigid_object_cfg in self.cfg.rigid_objects.items(): # obtain the first prim in the regex expression (all others are assumed to be a copy of this) @@ -737,15 +737,16 @@ def _invalidate_initialize_callback(self, event): # set all existing views to None to invalidate them self._root_physx_view = 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: This function is called when the prim is deleted. """ + prim_path = event.payload["prim_path"] if prim_path == "/": self._clear_callbacks() return diff --git a/source/isaaclab/isaaclab/controllers/rmp_flow.py b/source/isaaclab/isaaclab/controllers/rmp_flow.py index 61dfe6a8cc4..1cbe79e5cf8 100644 --- a/source/isaaclab/isaaclab/controllers/rmp_flow.py +++ b/source/isaaclab/isaaclab/controllers/rmp_flow.py @@ -6,7 +6,7 @@ import torch from dataclasses import MISSING -from isaacsim.core.api.simulation_context import SimulationContext +from isaaclab.sim import SimulationContext from isaacsim.core.prims import SingleArticulation # enable motion generation extensions diff --git a/source/isaaclab/isaaclab/envs/direct_marl_env.py b/source/isaaclab/isaaclab/envs/direct_marl_env.py index 97fb3ae3da5..e99fa75440e 100644 --- a/source/isaaclab/isaaclab/envs/direct_marl_env.py +++ b/source/isaaclab/isaaclab/envs/direct_marl_env.py @@ -5,7 +5,6 @@ from __future__ import annotations -import builtins import gymnasium as gym import inspect import logging @@ -122,7 +121,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() @@ -132,7 +131,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 @@ -150,17 +149,16 @@ def __init__(self, cfg: DirectMARLEnvCfg, render_mode: str | None = None, **kwar # play the simulator to activate physics handles # note: this activates the physics simulation view that exposes TensorAPIs # note: when started in extension mode, first call sim.reset_async() and then initialize the managers - if builtins.ISAAC_LAUNCHED_FROM_TERMINAL is False: - print("[INFO]: Starting the simulation. This may take a few seconds. Please wait...") - with Timer("[INFO]: Time taken for simulation start", "simulation_start"): - # since the reset can trigger callbacks which use the stage, - # we need to set the stage context here - with use_stage(self.sim.get_initial_stage()): - self.sim.reset() - # update scene to pre populate data buffers for assets and sensors. - # this is needed for the observation manager to get valid tensors for initialization. - # this shouldn't cause an issue since later on, users do a reset over all the environments so the lazy buffers would be reset. - self.scene.update(dt=self.physics_dt) + print("[INFO]: Starting the simulation. This may take a few seconds. Please wait...") + with Timer("[INFO]: Time taken for simulation start", "simulation_start"): + # since the reset can trigger callbacks which use the stage, + # we need to set the stage context here + with use_stage(self.sim.stage): + self.sim.reset() + # update scene to pre populate data buffers for assets and sensors. + # this is needed for the observation manager to get valid tensors for initialization. + # this shouldn't cause an issue since later on, users do a reset over all the environments so the lazy buffers would be reset. + self.scene.update(dt=self.physics_dt) # check if debug visualization is has been implemented by the environment source_code = inspect.getsource(self._set_debug_vis_impl) @@ -170,7 +168,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 @@ -256,7 +254,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: @@ -264,7 +262,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): @@ -279,7 +277,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)) """ Space methods @@ -372,7 +370,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): @@ -490,17 +488,17 @@ 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" is headless and offscreen rendering is disabled. Please set the simulation render mode to:" f"'{self.sim.RenderMode.PARTIAL_RENDERING.name}' or '{self.sim.RenderMode.FULL_RENDERING.name}'." " If running headless, make sure --enable_cameras is set." ) @@ -547,9 +545,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 22b8f3217c5..9234b581b0b 100644 --- a/source/isaaclab/isaaclab/envs/direct_rl_env.py +++ b/source/isaaclab/isaaclab/envs/direct_rl_env.py @@ -5,7 +5,6 @@ from __future__ import annotations -import builtins import gymnasium as gym import inspect import logging @@ -21,7 +20,7 @@ import omni.kit.app import omni.physx -from isaacsim.core.simulation_manager import SimulationManager +from isaaclab.physics.physx_manager import PhysxManager from isaaclab.managers import EventManager from isaaclab.scene import InteractiveScene @@ -129,7 +128,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() @@ -139,7 +138,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 @@ -157,17 +156,16 @@ def __init__(self, cfg: DirectRLEnvCfg, render_mode: str | None = None, **kwargs # play the simulator to activate physics handles # note: this activates the physics simulation view that exposes TensorAPIs # note: when started in extension mode, first call sim.reset_async() and then initialize the managers - if builtins.ISAAC_LAUNCHED_FROM_TERMINAL is False: - print("[INFO]: Starting the simulation. This may take a few seconds. Please wait...") - with Timer("[INFO]: Time taken for simulation start", "simulation_start"): - # since the reset can trigger callbacks which use the stage, - # we need to set the stage context here - with use_stage(self.sim.get_initial_stage()): - self.sim.reset() - # update scene to pre populate data buffers for assets and sensors. - # this is needed for the observation manager to get valid tensors for initialization. - # this shouldn't cause an issue since later on, users do a reset over all the environments so the lazy buffers would be reset. - self.scene.update(dt=self.physics_dt) + print("[INFO]: Starting the simulation. This may take a few seconds. Please wait...") + with Timer("[INFO]: Time taken for simulation start", "simulation_start"): + # since the reset can trigger callbacks which use the stage, + # we need to set the stage context here + with use_stage(self.sim.stage): + self.sim.reset() + # update scene to pre populate data buffers for assets and sensors. + # this is needed for the observation manager to get valid tensors for initialization. + # this shouldn't cause an issue since later on, users do a reset over all the environments so the lazy buffers would be reset. + self.scene.update(dt=self.physics_dt) # check if debug visualization is has been implemented by the environment source_code = inspect.getsource(self._set_debug_vis_impl) @@ -177,7 +175,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 @@ -258,7 +256,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: @@ -266,7 +264,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): @@ -281,7 +279,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. @@ -317,12 +315,12 @@ 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(): + if self.cfg.wait_for_textures and self.sim.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors"): + while PhysxManager.assets_loading(): self.sim.render() # return observations @@ -362,7 +360,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): @@ -395,7 +393,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() @@ -459,17 +457,17 @@ 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" is headless and offscreen rendering is disabled. Please set the simulation render mode to:" f"'{self.sim.RenderMode.PARTIAL_RENDERING.name}' or '{self.sim.RenderMode.FULL_RENDERING.name}'." " If running headless, make sure --enable_cameras is set." ) @@ -516,9 +514,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 564668d55f3..6d629ae766a 100644 --- a/source/isaaclab/isaaclab/envs/manager_based_env.py +++ b/source/isaaclab/isaaclab/envs/manager_based_env.py @@ -3,7 +3,6 @@ # # SPDX-License-Identifier: BSD-3-Clause -import builtins import logging import torch import warnings @@ -11,7 +10,7 @@ from typing import Any import omni.physx -from isaacsim.core.simulation_manager import SimulationManager +from isaaclab.physics.physx_manager import PhysxManager from isaaclab.managers import ActionManager, EventManager, ObservationManager, RecorderManager from isaaclab.scene import InteractiveScene @@ -67,7 +66,7 @@ class ManagerBasedEnv: The environment steps forward in time at a fixed time-step. The physics simulation is decimated at a lower time-step. This is to ensure that the simulation is stable. These two time-steps can be configured independently using the :attr:`ManagerBasedEnvCfg.decimation` (number of simulation steps per environment step) - and the :attr:`ManagerBasedEnvCfg.sim.dt` (physics time-step) parameters. Based on these parameters, the + and the :attr:`ManagerBasedEnvCfg.sim.physics_manager_cfg.dt` (physics time-step) parameters. Based on these parameters, the environment time-step is computed as the product of the two. The two time-steps can be obtained by querying the :attr:`physics_dt` and the :attr:`step_dt` properties respectively. """ @@ -101,11 +100,7 @@ def __init__(self, cfg: ManagerBasedEnvCfg): # since it gets confused with Isaac Sim's SimulationContext class self.sim: SimulationContext = SimulationContext(self.cfg.sim) else: - # simulation context should only be created before the environment - # when in extension mode - if not builtins.ISAAC_LAUNCHED_FROM_TERMINAL: - raise RuntimeError("Simulation context already exists. Cannot create a new one.") - self.sim: SimulationContext = SimulationContext.instance() + raise RuntimeError("Simulation context already exists. Cannot create a new one.") # make sure torch is running on the correct device if "cuda" in self.device: @@ -136,7 +131,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) @@ -145,7 +140,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 @@ -162,24 +157,23 @@ def __init__(self, cfg: ManagerBasedEnvCfg): # play the simulator to activate physics handles # note: this activates the physics simulation view that exposes TensorAPIs # note: when started in extension mode, first call sim.reset_async() and then initialize the managers - if builtins.ISAAC_LAUNCHED_FROM_TERMINAL is False: - print("[INFO]: Starting the simulation. This may take a few seconds. Please wait...") - with Timer("[INFO]: Time taken for simulation start", "simulation_start"): - # since the reset can trigger callbacks which use the stage, - # we need to set the stage context here - with use_stage(self.sim.get_initial_stage()): - self.sim.reset() - # update scene to pre populate data buffers for assets and sensors. - # this is needed for the observation manager to get valid tensors for initialization. - # this shouldn't cause an issue since later on, users do a reset over all the environments so the lazy buffers would be reset. - self.scene.update(dt=self.physics_dt) - # add timeline event to load managers - self.load_managers() + print("[INFO]: Starting the simulation. This may take a few seconds. Please wait...") + with Timer("[INFO]: Time taken for simulation start", "simulation_start"): + # since the reset can trigger callbacks which use the stage, + # we need to set the stage context here + with use_stage(self.sim.stage): + self.sim.reset() + # update scene to pre populate data buffers for assets and sensors. + # this is needed for the observation manager to get valid tensors for initialization. + # this shouldn't cause an issue since later on, users do a reset over all the environments so the lazy buffers would be reset. + self.scene.update(dt=self.physics_dt) + # add timeline event to load managers + self.load_managers() # extend UI elements # we need to do this here after all the managers are initialized # 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") @@ -227,7 +221,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: @@ -235,7 +229,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): @@ -371,7 +365,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() @@ -381,8 +375,8 @@ 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(): + if self.cfg.wait_for_textures and self.sim.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors"): + while PhysxManager.assets_loading(): self.sim.render() # return observations @@ -432,7 +426,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() @@ -451,7 +445,7 @@ def step(self, action: torch.Tensor) -> tuple[VecEnvObs, dict]: The environment steps forward at a fixed time-step, while the physics simulation is decimated at a lower time-step. This is to ensure that the simulation is stable. These two time-steps can be configured independently using the :attr:`ManagerBasedEnvCfg.decimation` (number of - simulation steps per environment step) and the :attr:`ManagerBasedEnvCfg.sim.dt` (physics time-step). + simulation steps per environment step) and the :attr:`ManagerBasedEnvCfg.sim.physics_manager_cfg.dt` (physics time-step). Based on these parameters, the environment time-step is computed as the product of the two. Args: @@ -467,7 +461,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): @@ -534,9 +528,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 44f6ed07ce1..5fee4871f00 100644 --- a/source/isaaclab/isaaclab/envs/manager_based_rl_env.py +++ b/source/isaaclab/isaaclab/envs/manager_based_rl_env.py @@ -174,7 +174,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): @@ -219,7 +219,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() @@ -262,17 +262,17 @@ 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" is headless and offscreen rendering is disabled. Please set the simulation render mode to:" f"'{self.sim.RenderMode.PARTIAL_RENDERING.name}' or '{self.sim.RenderMode.FULL_RENDERING.name}'." " If running headless, make sure --enable_cameras is set." ) diff --git a/source/isaaclab/isaaclab/envs/mdp/events.py b/source/isaaclab/isaaclab/envs/mdp/events.py index df7216d9d2e..35855724237 100644 --- a/source/isaaclab/isaaclab/envs/mdp/events.py +++ b/source/isaaclab/isaaclab/envs/mdp/events.py @@ -517,7 +517,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_manager_cfg.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( @@ -532,7 +532,7 @@ def randomize_physics_scene_gravity( gravity = gravity[0].tolist() # set the gravity into the physics simulation - physics_sim_view: physx.SimulationView = sim_utils.SimulationContext.instance().physics_sim_view + physics_sim_view: physx.SimulationView = sim_utils.SimulationContext.instance()._physics_interface.physics_sim_view physics_sim_view.set_gravity(carb.Float3(*gravity)) diff --git a/source/isaaclab/isaaclab/envs/ui/base_env_window.py b/source/isaaclab/isaaclab/envs/ui/base_env_window.py index 2aafe5e6bba..1ac9e0ac613 100644 --- a/source/isaaclab/isaaclab/envs/ui/base_env_window.py +++ b/source/isaaclab/isaaclab/envs/ui/base_env_window.py @@ -19,6 +19,7 @@ from isaaclab.sim.utils.stage import get_current_stage from isaaclab.ui.widgets import ManagerLiveVisualizer +from isaaclab.visualizers.ov_visualizer import RenderMode if TYPE_CHECKING: import omni.ui @@ -122,15 +123,27 @@ def _build_sim_frame(self): with self.ui_window_elements["sim_frame"]: # create stack for controls self.ui_window_elements["sim_vstack"] = omni.ui.VStack(spacing=5, height=0) + if not self.env.sim.carb_settings.get("/isaaclab/has_gui"): + if not self.env.sim.carb_settings.get_as_bool("/isaaclab/render/offscreen"): + render_value = RenderMode.NO_GUI_OR_RENDERING + else: + render_value = RenderMode.PARTIAL_RENDERING + else: + render_value = RenderMode.FULL_RENDERING + + for visualizer in self.env.sim._visualizer_interface._visualizers: + if hasattr(visualizer, "set_render_mode"): + set_render_mode_fn = lambda value: visualizer.set_render_mode(RenderMode[value]) + 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]), + "default_val": render_value, + "items": [member.name for member in RenderMode if member.value >= 0], + "tooltip": "Select a rendering mode\n" + RenderMode.__doc__, + "on_clicked_fn": lambda value: set_render_mode_fn(RenderMode[value]), } self.ui_window_elements["render_dropdown"] = isaacsim.gui.components.ui_utils.dropdown_builder( **render_mode_cfg @@ -149,7 +162,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.carb_settings.get_as_bool("/isaaclab/fabric_enabled") def _build_viewer_frame(self): """Build the viewer-related control frame for the UI.""" @@ -448,7 +461,7 @@ async def _dock_window(self, window_title: str): for _ in range(5): if omni.ui.Workspace.get_window(window_title): break - await self.env.sim.app.next_update_async() + await omni.kit.app.get_app().next_update_async() # dock next to properties window custom_window = omni.ui.Workspace.get_window(window_title) diff --git a/source/isaaclab/isaaclab/envs/ui/empty_window.py b/source/isaaclab/isaaclab/envs/ui/empty_window.py index bc12f862d1b..4302a51677d 100644 --- a/source/isaaclab/isaaclab/envs/ui/empty_window.py +++ b/source/isaaclab/isaaclab/envs/ui/empty_window.py @@ -69,7 +69,7 @@ async def _dock_window(self, window_title: str): for _ in range(5): if omni.ui.Workspace.get_window(window_title): break - await self.env.sim.app.next_update_async() + await omni.kit.app.get_app().next_update_async() # dock next to properties window custom_window = omni.ui.Workspace.get_window(window_title) diff --git a/source/isaaclab/isaaclab/envs/ui/viewport_camera_controller.py b/source/isaaclab/isaaclab/envs/ui/viewport_camera_controller.py index 6eb332dcdc4..97d1304c927 100644 --- a/source/isaaclab/isaaclab/envs/ui/viewport_camera_controller.py +++ b/source/isaaclab/isaaclab/envs/ui/viewport_camera_controller.py @@ -216,7 +216,7 @@ def update_view_location(self, eye: Sequence[float] | None = None, lookat: Seque cam_target = viewer_origin + self.default_cam_lookat # set the camera view - self._env.sim.set_camera_view(eye=cam_eye, target=cam_target) + self._env.sim._visualizer_interface.set_camera_view(eye=cam_eye, target=cam_target) """ Private Functions diff --git a/source/isaaclab/isaaclab/managers/recorder_manager.py b/source/isaaclab/isaaclab/managers/recorder_manager.py index dd254dc145b..9e1b6047601 100644 --- a/source/isaaclab/isaaclab/managers/recorder_manager.py +++ b/source/isaaclab/isaaclab/managers/recorder_manager.py @@ -437,7 +437,7 @@ def get_ep_meta(self) -> dict: # Add basic episode metadata ep_meta = dict() ep_meta["sim_args"] = { - "dt": self._env.cfg.sim.dt, + "dt": self._env.cfg.sim.physics_manager_cfg.dt, "decimation": self._env.cfg.decimation, "render_interval": self._env.cfg.sim.render_interval, "num_envs": self._env.cfg.scene.num_envs, diff --git a/source/isaaclab/isaaclab/physics/__init__.py b/source/isaaclab/isaaclab/physics/__init__.py new file mode 100644 index 00000000000..ad93e53f69d --- /dev/null +++ b/source/isaaclab/isaaclab/physics/__init__.py @@ -0,0 +1,24 @@ +# 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 +from .physics_manager_cfg import PhysicsManagerCfg +from .physx_manager import PhysxManager, IsaacEvents +from .physx_manager_cfg import PhysxManagerCfg +# from .newton_manager import NewtonManager +# from .newton_manager_cfg import NewtonManagerCfg + + +__all__ = [ + "PhysicsManager", + "PhysicsManagerCfg", + "PhysxManager", + "IsaacEvents", + "PhysxManagerCfg", + # "NewtonManager", + # "NewtonManagerCfg", +] diff --git a/source/isaaclab/isaaclab/physics/newton_manager.py b/source/isaaclab/isaaclab/physics/newton_manager.py new file mode 100644 index 00000000000..c734358f740 --- /dev/null +++ b/source/isaaclab/isaaclab/physics/newton_manager.py @@ -0,0 +1,551 @@ +# 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 physics manager for Isaac Lab.""" + +from __future__ import annotations + +import numpy as np +import re +from typing import TYPE_CHECKING + +import warp as wp +from newton import Axis, Contacts, Control, Model, ModelBuilder, State, eval_fk +from newton.examples import create_collision_pipeline +from newton.sensors import ContactSensor as NewtonContactSensor +from newton.sensors import populate_contacts +from newton.solvers import SolverBase, SolverFeatherstone, SolverMuJoCo, SolverNotifyFlags, SolverXPBD + +from isaaclab.sim.utils.stage import get_current_stage +from isaaclab.utils.timer import Timer + +from .physics_manager import PhysicsManager + +if TYPE_CHECKING: + from isaaclab.sim.simulation_context import SimulationContext + from .newton_manager_cfg import NewtonManagerCfg + from .solvers_cfg import NewtonSolverCfg + + +def flipped_match(x: str, y: str) -> re.Match | None: + """Flipped match function. + + This function is used to match the contact partners' body/shape names with the body/shape names in the simulation. + + Args: + x: The body/shape name in the simulation. + y: The body/shape name in the contact view. + + Returns: + The match object if the body/shape name is found in the contact view, otherwise None. + """ + return re.match(y, x) + + +class NewtonManager(PhysicsManager): + """Newton physics manager for Isaac Lab. + + This is a class-level (singleton-like) manager for the Newton simulation. + It handles solver configuration, physics stepping, and reset. + + Lifecycle: initialize() -> reset() -> step() (repeated) -> close() + """ + + # Simulation context reference + _sim: "SimulationContext | None" = None + + # Manager configuration + _cfg: "NewtonManagerCfg | None" = None + + # Newton-specific state + _builder: ModelBuilder = None + _model: Model = None + _device: str = "cuda:0" + _dt: float = 1.0 / 200.0 + _solver_dt: float = 1.0 / 200.0 + _num_substeps: int = 1 + _solver = None + _state_0: State = None + _state_1: State = None + _state_temp: State = None + _control: Control = None + _on_init_callbacks: list = [] + _on_start_callbacks: list = [] + _contacts: Contacts = None + _needs_collision_pipeline: bool = False + _collision_pipeline = None + _newton_contact_sensor: NewtonContactSensor = None # TODO: allow several contact sensors + _report_contacts: bool = False + _graph = None + _newton_stage_path = None + _sim_time = 0.0 + _usdrt_stage = None + _newton_index_attr = "newton:index" + _clone_physics_only = False + _solver_type: str = "mujoco_warp" + _gravity_vector: tuple[float, float, float] = (0.0, 0.0, -9.81) + _up_axis: str = "Z" + _num_envs: int | None = None + _model_changes: set[int] = set() + + # ------------------------------------------------------------------ + # PhysicsManager Interface + # ------------------------------------------------------------------ + + @classmethod + def initialize(cls, sim_context: "SimulationContext") -> None: + """Initialize the manager with simulation context. + + Args: + sim_context: Parent simulation context. + """ + cls._sim = sim_context + cls._cfg = sim_context.cfg.physics_manager_cfg # type: ignore[assignment] + + # Set simulation parameters from config (device comes from sim_context, not cfg) + cls._dt = cls._cfg.dt + cls._device = sim_context.device + cls._gravity_vector = cls._cfg.gravity + + # USD fabric sync only needed for OV rendering + if cls._sim is not None: + cls._clone_physics_only = "omniverse" not in cls._sim._visualizer_interface._visualizers_str # type: ignore[union-attr] + + @classmethod + def reset(cls, soft: bool = False) -> None: + """Reset physics simulation. + + Args: + soft: If True, skip full reinitialization. + """ + if not soft: + cls.start_simulation() + cls.initialize_solver() + + @classmethod + def forward(cls) -> None: + """Update articulation kinematics without stepping physics.""" + cls.forward_kinematics() + + @classmethod + def step(cls) -> None: + """Step the physics simulation.""" + if cls._sim is not None and cls._sim.is_playing(): + cls._step_internal() + + @classmethod + def close(cls) -> None: + """Clean up Newton physics resources.""" + cls.clear() + cls._sim = None + cls._cfg = None + + @classmethod + def get_physics_dt(cls) -> float: + """Get the physics timestep in seconds.""" + return cls._dt + + @classmethod + def get_device(cls) -> str: + """Get the physics simulation device.""" + return cls._device + + @classmethod + def get_physics_sim_view(cls): + """Get the physics simulation view (not applicable for Newton).""" + return None + + @classmethod + def is_fabric_enabled(cls) -> bool: + """Check if fabric interface is enabled (not applicable for Newton).""" + return False + + # ------------------------------------------------------------------ + # Newton-specific API + # ------------------------------------------------------------------ + + @classmethod + def clear(cls): + """Clear all state.""" + cls._builder = None + cls._model = None + cls._solver = None + cls._state_0 = None + cls._state_1 = None + cls._state_temp = None + cls._control = None + cls._contacts = None + cls._needs_collision_pipeline = False + cls._collision_pipeline = None + cls._newton_contact_sensor = None + cls._report_contacts = False + cls._graph = None + cls._newton_stage_path = None + cls._sim_time = 0.0 + cls._on_init_callbacks = [] + cls._on_start_callbacks = [] + cls._usdrt_stage = None + cls._up_axis = "Z" + cls._model_changes = set() + + @classmethod + def set_builder(cls, builder): + cls._builder = builder + + @classmethod + def add_on_init_callback(cls, callback) -> None: + cls._on_init_callbacks.append(callback) + + @classmethod + def add_on_start_callback(cls, callback) -> None: + cls._on_start_callbacks.append(callback) + + @classmethod + def add_model_change(cls, change: SolverNotifyFlags) -> None: + cls._model_changes.add(change) + + @classmethod + def start_simulation(cls) -> None: + """Starts the simulation. + + This function finalizes the model and initializes the simulation state. + """ + + print(f"[INFO] Builder: {cls._builder}") + if cls._builder is None: + cls.instantiate_builder_from_stage() + print("[INFO] Running on init callbacks") + for callback in cls._on_init_callbacks: + callback() + print(f"[INFO] Finalizing model on device: {cls._device}") + cls._builder.gravity = np.array(cls._gravity_vector)[-1] + cls._builder.up_axis = Axis.from_string(cls._up_axis) + with Timer(name="newton_finalize_builder", msg="Finalize builder took:", enable=True, format="ms"): + cls._model = cls._builder.finalize(device=cls._device) + cls._model.num_envs = cls._num_envs + cls._state_0 = cls._model.state() + cls._state_1 = cls._model.state() + cls._state_temp = cls._model.state() + cls._control = cls._model.control() + cls.forward_kinematics() + if cls._needs_collision_pipeline: + cls._collision_pipeline = create_collision_pipeline(cls._model) + cls._contacts = cls._model.collide( + cls._state_0, collision_pipeline=cls._collision_pipeline + ) + else: + cls._contacts = Contacts(0, 0) + print("[INFO] Running on start callbacks") + for callback in cls._on_start_callbacks: + callback() + if not cls._clone_physics_only: + import usdrt + + cls._usdrt_stage = get_current_stage(fabric=True) + for i, prim_path in enumerate(cls._model.body_key): + prim = cls._usdrt_stage.GetPrimAtPath(prim_path) + prim.CreateAttribute(cls._newton_index_attr, usdrt.Sdf.ValueTypeNames.UInt, True) + prim.GetAttribute(cls._newton_index_attr).Set(i) + xformable_prim = usdrt.Rt.Xformable(prim) + if not xformable_prim.HasWorldXform(): + xformable_prim.SetWorldXformFromUsd() + + @classmethod + def instantiate_builder_from_stage(cls): + from pxr import UsdGeom + + stage = get_current_stage() + up_axis = UsdGeom.GetStageUpAxis(stage) + builder = ModelBuilder(up_axis=up_axis) + builder.add_usd(stage) + cls.set_builder(builder) + + @classmethod + def set_solver_settings(cls, cfg: "NewtonManagerCfg") -> None: + """Set solver settings from config. + + Args: + cfg: Newton manager configuration. + """ + cls._cfg = cfg + + @classmethod + def initialize_solver(cls): + """Initializes the solver. + + This function initializes the solver based on the specified solver type. Currently, only XPBD and MuJoCoWarp + are supported. The graphing of the simulation is performed in this function if the simulation is ran using + a CUDA enabled device. + + .. warning:: + When using a CUDA enabled device, the simulation will be graphed. This means that this function steps the + simulation once to capture the graph. Hence, this function should only be called after everything else in + the simulation is initialized. + """ + if cls._cfg is None: + return + + with Timer(name="newton_initialize_solver", msg="Initialize solver took:", enable=True, format="ms"): + cls._num_substeps = cls._cfg.num_substeps + cls._solver_dt = cls._dt / cls._num_substeps + print(cls._model.gravity) + cls._solver = cls._get_solver(cls._model, cls._cfg.solver_cfg) + if isinstance(cls._solver, SolverMuJoCo): + use_mujoco_contacts = getattr(cls._cfg.solver_cfg, "use_mujoco_contacts", False) + cls._needs_collision_pipeline = not use_mujoco_contacts + else: + cls._needs_collision_pipeline = True + + # Ensure we are using a CUDA enabled device + assert cls._device.startswith("cuda"), "NewtonManager only supports CUDA enabled devices" + + # Capture the graph if CUDA is enabled + with Timer(name="newton_cuda_graph", msg="CUDA graph took:", enable=True, format="ms"): + if cls._cfg.use_cuda_graph: + with wp.ScopedCapture() as capture: + cls.simulate() + cls._graph = capture.graph + + @classmethod + def simulate(cls) -> None: + """Simulates the simulation. + + Performs one simulation step with the specified number of substeps. Depending on the solver type, this function + may need to explicitly compute the collisions. This function also aggregates the contacts and evaluates the + contact sensors. Finally, it performs the state swapping for Newton. + """ + state_0_dict = cls._state_0.__dict__ + state_1_dict = cls._state_1.__dict__ + state_temp_dict = cls._state_temp.__dict__ + contacts = None + + # MJWarp computes its own collisions. + if cls._needs_collision_pipeline: + contacts = cls._model.collide( + cls._state_0, collision_pipeline=cls._collision_pipeline + ) + + if cls._num_substeps % 2 == 0: + for i in range(cls._num_substeps): + cls._solver.step( + cls._state_0, + cls._state_1, + cls._control, + contacts, + cls._solver_dt, + ) + cls._state_0, cls._state_1 = cls._state_1, cls._state_0 + cls._state_0.clear_forces() + else: + for i in range(cls._num_substeps): + cls._solver.step( + cls._state_0, + cls._state_1, + cls._control, + contacts, + cls._solver_dt, + ) + + # FIXME: Ask Lukasz help to deal with non-even number of substeps. This should not be needed. + if i < cls._num_substeps - 1 or not cls._cfg.use_cuda_graph: + # we can just swap the state references + cls._state_0, cls._state_1 = cls._state_1, cls._state_0 + elif cls._cfg.use_cuda_graph: + # swap states by actually copying the state arrays to make sure the graph capture works + for key, value in state_0_dict.items(): + if isinstance(value, wp.array): # type: ignore[arg-type] + if key not in state_temp_dict: + state_temp_dict[key] = wp.empty_like(value) + state_temp_dict[key].assign(value) + state_0_dict[key].assign(state_1_dict[key]) + state_1_dict[key].assign(state_temp_dict[key]) + cls._state_0.clear_forces() + + if cls._report_contacts: + populate_contacts(cls._contacts, cls._solver) + cls._newton_contact_sensor.eval(cls._contacts) + + @classmethod + def set_device(cls, device: str) -> None: + """Sets the device to use for the Newton simulation. + + Args: + device (str): The device to use for the Newton simulation. + """ + cls._device = device + + @classmethod + def _step_internal(cls) -> None: + """Steps the simulation (internal). + + This function steps the simulation by the specified time step in the simulation configuration. + """ + if cls._model_changes: + for change in cls._model_changes: + cls._solver.notify_model_changed(change) + cls._model_changes = set() + + if cls._cfg is not None and cls._cfg.use_cuda_graph: + wp.capture_launch(cls._graph) # type: ignore[arg-type] + else: + cls.simulate() + + if cls._cfg is not None and cls._cfg.debug_mode: + convergence_data = cls.get_solver_convergence_steps() + # print(f"solver niter: {convergence_data}") + if convergence_data["max"] == cls._solver.mjw_model.opt.iterations: + print("solver didn't converge!", convergence_data["max"]) + + cls._sim_time += cls._solver_dt * cls._num_substeps + + @classmethod + def get_solver_convergence_steps(cls) -> dict[str, float | int]: + niter = cls._solver.mjw_data.solver_niter.numpy() + max_niter = np.max(niter) + mean_niter = np.mean(niter) + min_niter = np.min(niter) + std_niter = np.std(niter) + return {"max": max_niter, "mean": mean_niter, "min": min_niter, "std": std_niter} + + @classmethod + def set_simulation_dt(cls, dt: float) -> None: + """Sets the simulation time step and the number of substeps. + + Args: + dt (float): The simulation time step. + """ + cls._dt = dt + + @classmethod + def get_model(cls): + return cls._model + + @classmethod + def get_state_0(cls): + return cls._state_0 + + @classmethod + def get_state_1(cls): + return cls._state_1 + + @classmethod + def get_control(cls): + return cls._control + + @classmethod + def get_dt(cls): + return cls._dt + + @classmethod + def get_solver_dt(cls): + return cls._solver_dt + + @classmethod + def forward_kinematics(cls, mask: wp.array | None = None) -> None: + """Evaluates the forward kinematics for the selected articulations. + + This function evaluates the forward kinematics for the selected articulations. + """ + eval_fk( + cls._model, + cls._state_0.joint_q, + cls._state_0.joint_qd, + cls._state_0, + None, + ) + + @classmethod + def _get_solver(cls, model: Model, solver_cfg: "NewtonSolverCfg") -> SolverBase: + """Create and return the appropriate solver based on config. + + Args: + model: The Newton model. + solver_cfg: Solver configuration. + + Returns: + The initialized solver. + """ + # Convert config to dict if needed (configclass adds to_dict method) + if hasattr(solver_cfg, "to_dict"): + cfg_dict = solver_cfg.to_dict() # type: ignore[union-attr] + else: + cfg_dict = dict(solver_cfg) if isinstance(solver_cfg, dict) else {} # type: ignore[arg-type] + + cls._solver_type = cfg_dict.pop("solver_type", "mujoco_warp") + + if cls._solver_type == "mujoco_warp": + return SolverMuJoCo(model, **cfg_dict) + elif cls._solver_type == "xpbd": + return SolverXPBD(model, **cfg_dict) + elif cls._solver_type == "featherstone": + return SolverFeatherstone(model, **cfg_dict) + else: + raise ValueError(f"Invalid solver type: {cls._solver_type}") + + @classmethod + def add_contact_sensor( + cls, + body_names_expr: str | list[str] | None = None, + shape_names_expr: str | list[str] | None = None, + contact_partners_body_expr: str | list[str] | None = None, + contact_partners_shape_expr: str | list[str] | None = None, + prune_noncolliding: bool = False, + verbose: bool = False, + ): + """Adds a contact view. + + Adds a contact view to the simulation allowing to report contacts between the specified bodies/shapes and the + contact partners. As of now, only one body/shape name expression can be provided. Similarly, only one contact + partner body/shape expression can be provided. If no contact partner expression is provided, the contact view + will report contacts with all bodies/shapes. + + Note that we make an explicit difference between a body and a shape. A body is a rigid body, while a shape + is a collision shape. A body can have multiple shapes. The shape option allows a more fine-grained control + over the contact reporting. + + Args: + body_names_expr (str | None): The expression for the body names. + shape_names_expr (str | None): The expression for the shape names. + contact_partners_body_expr (str | None): The expression for the contact partners' body names. + contact_partners_shape_expr (str | None): The expression for the contact partners' shape names. + prune_noncolliding (bool): Make the force matrix sparse using the collision pairs in the model. + verbose (bool): Whether to print verbose information. + """ + if body_names_expr is None and shape_names_expr is None: + raise ValueError("At least one of body_names_expr or shape_names_expr must be provided") + if body_names_expr is not None and shape_names_expr is not None: + raise ValueError("Only one of body_names_expr or shape_names_expr must be provided") + if contact_partners_body_expr is not None and contact_partners_shape_expr is not None: + raise ValueError("Only one of contact_partners_body_expr or contact_partners_shape_expr must be provided") + if contact_partners_body_expr is None and contact_partners_shape_expr is None: + print(f"[INFO] Adding contact view for {body_names_expr}. It will report contacts with all bodies/shapes.") + else: + if body_names_expr is not None: + if contact_partners_body_expr is not None: + print(f"[INFO] Adding contact view for {body_names_expr} with filter {contact_partners_body_expr}.") + else: + print(f"[INFO] Adding contact view for {body_names_expr} with filter {shape_names_expr}.") + else: + if contact_partners_body_expr is not None: + print( + f"[INFO] Adding contact view for {shape_names_expr} with filter {contact_partners_body_expr}." + ) + else: + print( + f"[INFO] Adding contact view for {shape_names_expr} with filter {contact_partners_shape_expr}." + ) + + cls._newton_contact_sensor = NewtonContactSensor( + cls._model, + sensing_obj_bodies=body_names_expr, + sensing_obj_shapes=shape_names_expr, + counterpart_bodies=contact_partners_body_expr, + counterpart_shapes=contact_partners_shape_expr, + match_fn=flipped_match, + include_total=True, + prune_noncolliding=prune_noncolliding, + verbose=verbose, + ) + cls._report_contacts = True diff --git a/source/isaaclab/isaaclab/physics/newton_manager_cfg.py b/source/isaaclab/isaaclab/physics/newton_manager_cfg.py new file mode 100644 index 00000000000..a2dd6e5edcd --- /dev/null +++ b/source/isaaclab/isaaclab/physics/newton_manager_cfg.py @@ -0,0 +1,224 @@ +# 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 physics manager.""" + +from __future__ import annotations + +from typing import TYPE_CHECKING + +from isaaclab.utils import configclass + +from .physics_manager_cfg import PhysicsManagerCfg + +if TYPE_CHECKING: + from .physics_manager import PhysicsManager + + +@configclass +class NewtonSolverCfg: + """Configuration for Newton solver-related parameters. + + These parameters are used to configure the Newton solver. For more information, see the `Newton documentation`_. + + .. _Newton documentation: https://newton.readthedocs.io/en/latest/ + """ + + solver_type: str = "None" + """Solver type. + + Used to select the right solver class. + """ + + +@configclass +class MJWarpSolverCfg(NewtonSolverCfg): + """Configuration for MuJoCo Warp solver-related parameters. + + These parameters are used to configure the MuJoCo Warp solver. For more information, see the + `MuJoCo Warp documentation`_. + + .. _MuJoCo Warp documentation: https://github.com/google-deepmind/mujoco_warp + """ + + solver_type: str = "mujoco_warp" + """Solver type. Can be "mujoco_warp".""" + + njmax: int = 300 + """Number of constraints per environment (world).""" + + nconmax: int | None = None + """Number of contact points per environment (world).""" + + iterations: int = 100 + """Number of solver iterations.""" + + ls_iterations: int = 50 + """Number of line search iterations for the solver.""" + + solver: str = "newton" + """Solver type. Can be "cg" or "newton", or their corresponding MuJoCo integer constants.""" + + integrator: str = "euler" + """Integrator type. Can be "euler", "rk4", or "implicit", or their corresponding MuJoCo integer constants.""" + + use_mujoco_cpu: bool = False + """Whether to use the pure MuJoCo backend instead of `mujoco_warp`.""" + + disable_contacts: bool = False + """Whether to disable contact computation in MuJoCo.""" + + default_actuator_gear: float | None = None + """Default gear ratio for all actuators.""" + + actuator_gears: dict[str, float] | None = None + """Dictionary mapping joint names to specific gear ratios, overriding the `default_actuator_gear`.""" + + update_data_interval: int = 1 + """Frequency (in simulation steps) at which to update the MuJoCo Data object from the Newton state. + + If 0, Data is never updated after initialization. + """ + + save_to_mjcf: str | None = None + """Optional path to save the generated MJCF model file. + + If None, the MJCF model is not saved. + """ + + impratio: float = 1.0 + """Frictional-to-normal constraint impedance ratio.""" + + cone: str = "pyramidal" + """The type of contact friction cone. Can be "pyramidal" or "elliptic".""" + + ls_parallel: bool = False + """Whether to use parallel line search.""" + + use_mujoco_contacts: bool = True + """Whether to use MuJoCo's contact solver.""" + + +@configclass +class XPBOSolverCfg(NewtonSolverCfg): + """An implicit integrator using eXtended Position-Based Dynamics (XPBD) for rigid and soft body simulation. + + References: + - Miles Macklin, Matthias Müller, and Nuttapong Chentanez. 2016. XPBD: position-based simulation of compliant + constrained dynamics. In Proceedings of the 9th International Conference on Motion in Games (MIG '16). + Association for Computing Machinery, New York, NY, USA, 49-54. https://doi.org/10.1145/2994258.2994272 + - Matthias Müller, Miles Macklin, Nuttapong Chentanez, Stefan Jeschke, and Tae-Yong Kim. 2020. Detailed rigid + body simulation with extended position based dynamics. In Proceedings of the ACM SIGGRAPH/Eurographics + Symposium on Computer Animation (SCA '20). Eurographics Association, Goslar, DEU, + Article 10, 1-12. https://doi.org/10.1111/cgf.14105 + + """ + + solver_type: str = "xpbd" + """Solver type. Can be "xpbd".""" + + iterations: int = 2 + """Number of solver iterations.""" + + soft_body_relaxation: float = 0.9 + """Relaxation parameter for soft body simulation.""" + + soft_contact_relaxation: float = 0.9 + """Relaxation parameter for soft contact simulation.""" + + joint_linear_relaxation: float = 0.7 + """Relaxation parameter for joint linear simulation.""" + + joint_angular_relaxation: float = 0.4 + """Relaxation parameter for joint angular simulation.""" + + joint_linear_compliance: float = 0.0 + """Compliance parameter for joint linear simulation.""" + + joint_angular_compliance: float = 0.0 + """Compliance parameter for joint angular simulation.""" + + rigid_contact_relaxation: float = 0.8 + """Relaxation parameter for rigid contact simulation.""" + + rigid_contact_con_weighting: bool = True + """Whether to use contact constraint weighting for rigid contact simulation.""" + + angular_damping: float = 0.0 + """Angular damping parameter for rigid contact simulation.""" + + enable_restitution: bool = False + """Whether to enable restitution for rigid contact simulation.""" + + +@configclass +class FeatherstoneSolverCfg(NewtonSolverCfg): + """A semi-implicit integrator using symplectic Euler. + + It operates on reduced (also called generalized) coordinates to simulate articulated rigid body dynamics + based on Featherstone's composite rigid body algorithm (CRBA). + + See: Featherstone, Roy. Rigid Body Dynamics Algorithms. Springer US, 2014. + + Semi-implicit time integration is a variational integrator that + preserves energy, however it not unconditionally stable, and requires a time-step + small enough to support the required stiffness and damping forces. + + See: https://en.wikipedia.org/wiki/Semi-implicit_Euler_method + """ + + solver_type: str = "featherstone" + """Solver type. Can be "featherstone".""" + + angular_damping: float = 0.05 + """Angular damping parameter for rigid contact simulation.""" + + update_mass_matrix_interval: int = 1 + """Frequency (in simulation steps) at which to update the mass matrix.""" + + friction_smoothing: float = 1.0 + """Friction smoothing parameter.""" + + use_tile_gemm: bool = False + """Whether to use tile-based GEMM for the mass matrix.""" + + fuse_cholesky: bool = True + """Whether to fuse the Cholesky decomposition.""" + + +@configclass +class NewtonManagerCfg(PhysicsManagerCfg): + """Configuration for Newton physics manager. + + This configuration includes Newton-specific simulation settings and solver configuration. + """ + + num_substeps: int = 1 + """Number of substeps to use for the solver.""" + + debug_mode: bool = False + """Whether to enable debug mode for the solver.""" + + use_cuda_graph: bool = True + """Whether to use CUDA graphing when simulating. + + If set to False, the simulation performance will be severely degraded. + """ + + solver_cfg: NewtonSolverCfg = MJWarpSolverCfg() + """Solver configuration. Default is MJWarpSolverCfg().""" + + # ------------------------------------------------------------------ + # Factory Method + # ------------------------------------------------------------------ + + def create_manager(self) -> type["PhysicsManager"]: + """Create and return the NewtonManager class. + + Returns: + The NewtonManager class. + """ + from .newton_manager import NewtonManager + return NewtonManager diff --git a/source/isaaclab/isaaclab/physics/physics_manager.py b/source/isaaclab/isaaclab/physics/physics_manager.py new file mode 100644 index 00000000000..a8382149e02 --- /dev/null +++ b/source/isaaclab/isaaclab/physics/physics_manager.py @@ -0,0 +1,86 @@ +# 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.""" + +from __future__ import annotations + +from abc import ABC, abstractmethod +from typing import TYPE_CHECKING + +if TYPE_CHECKING: + from isaaclab.sim.simulation_context import SimulationContext + + +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. + + Lifecycle: __init__() -> reset() -> step() (repeated) -> close() + """ + + @classmethod + @abstractmethod + def initialize(cls, sim_context: "SimulationContext") -> None: + """Initialize the physics manager with simulation context. + + Args: + sim_context: Parent simulation context. + """ + pass + + @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 + @abstractmethod + def close(cls) -> None: + """Clean up physics resources.""" + pass + + @classmethod + @abstractmethod + def get_physics_dt(cls) -> float: + """Get the physics timestep in seconds.""" + pass + + @classmethod + @abstractmethod + def get_device(cls) -> str: + """Get the physics simulation device.""" + pass + + @classmethod + @abstractmethod + def get_physics_sim_view(cls): + """Get the physics simulation view.""" + pass + + @classmethod + @abstractmethod + def is_fabric_enabled(cls) -> bool: + """Check if fabric interface is enabled.""" + pass 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..e523834b816 --- /dev/null +++ b/source/isaaclab/isaaclab/physics/physics_manager_cfg.py @@ -0,0 +1,60 @@ +# 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 isaaclab.utils import configclass + +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 + # ------------------------------------------------------------------ + + 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).""" + + # ------------------------------------------------------------------ + # Factory Method + # ------------------------------------------------------------------ + + def create_manager(self) -> type["PhysicsManager"]: + """Create and return the physics manager class for this configuration. + + Returns: + The physics manager class (not an instance). + + Raises: + NotImplementedError: If not overridden by subclass. + """ + raise NotImplementedError("Subclasses must implement create_manager()") diff --git a/source/isaaclab/isaaclab/physics/physx_manager.py b/source/isaaclab/isaaclab/physics/physx_manager.py new file mode 100644 index 00000000000..3cf936a9adc --- /dev/null +++ b/source/isaaclab/isaaclab/physics/physx_manager.py @@ -0,0 +1,867 @@ +# 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 +import weakref +from collections import OrderedDict +from datetime import datetime +from enum import Enum +from typing import TYPE_CHECKING, Any, Callable, ClassVar + +import carb +import omni.kit +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 .physics_manager import PhysicsManager + +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.""" + + 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" + + +class AnimationRecorder: + """Handles animation recording for the simulation. + + This class manages the recording of physics animations using the PhysX PVD + (Physics Visual Debugger) interface. It handles the setup, update, and + finalization of animation recordings. + """ + + def __init__(self, carb_settings: carb.settings.ISettings, app_iface: omni.kit.app.IApp): + """Initialize the animation recorder. + + Args: + carb_settings: The Carbonite settings interface. + app_iface: The Omniverse Kit application interface. + """ + self._carb_settings = carb_settings + self._app_iface = app_iface + self._enabled = False + self._start_time: float = 0.0 + self._stop_time: float = 0.0 + self._started_timestamp: float | None = None + self._output_dir: str = "" + self._timestamp: str = "" + self._physx_pvd_interface = None + + self._setup() + + @property + def enabled(self) -> bool: + """Whether animation recording is enabled.""" + return self._enabled + + def _setup(self) -> None: + """Sets up animation recording settings and initializes the recording.""" + self._enabled = bool(self._carb_settings.get("/isaaclab/anim_recording/enabled")) + if not self._enabled: + return + + # Import omni.physx.pvd.bindings here since it is not available by default + from omni.physxpvd.bindings import _physxPvd + + # Init anim recording settings + self._start_time = self._carb_settings.get("/isaaclab/anim_recording/start_time") + self._stop_time = self._carb_settings.get("/isaaclab/anim_recording/stop_time") + self._started_timestamp = None + + # Make output path relative to repo path + repo_path = os.path.join(carb.tokens.get_tokens_interface().resolve("${app}"), "..") + self._timestamp = datetime.now().strftime("%Y_%m_%d_%H%M%S") + self._output_dir = ( + os.path.join(repo_path, "anim_recordings", self._timestamp).replace("\\", "/").rstrip("/") + "/" + ) + os.makedirs(self._output_dir, exist_ok=True) + + # Acquire physx pvd interface and set output directory + self._physx_pvd_interface = _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._output_dir) + self._carb_settings.set_bool("/physics/omniPvdOutputEnabled", True) + + def update(self) -> bool: + """Tracks timestamps and triggers finish if total time has elapsed. + + Returns: + True if animation recording has finished, False otherwise. + """ + if not self._enabled: + return False + + if self._started_timestamp is None: + self._started_timestamp = time.time() + + total_time = time.time() - self._started_timestamp + if total_time > self._stop_time: + self._finish() + return True + return False + + def _finish(self) -> bool: + """Finishes the animation recording and outputs the baked animation recording. + + Returns: + True if the recording was successfully finished. + """ + 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._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._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" + if self._physx_pvd_interface is None: + return False + result = self._physx_pvd_interface.ovd_to_usd_over_with_layer_creation( + input_ovd_path, + stage_path, + self._output_dir, + stage_filename, + self._start_time, + self._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._output_dir, stage_filename), self._start_time) + + # Disable recording + self._carb_settings.set_bool("/physics/omniPvdOutputEnabled", False) + + return result + + @staticmethod + def _update_usda_start_time(file_path: str, start_time: float) -> None: + """Updates the start time of the USDA baked animation recording file. + + Args: + file_path: Path to the USDA file. + start_time: The new start time to set. + """ + # 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) + + +class PhysxManager(PhysicsManager): + """Manages PhysX physics simulation lifecycle, configuration, callbacks, and physics views. + + This is a class-level (singleton-like) manager for the PhysX simulation. + It handles device settings (CPU/GPU), timestep/solver configuration, + fabric interface for fast data access, physics stepping, and reset. + + Lifecycle: initialize() -> reset() -> step() (repeated) -> close() + """ + + # ==================== Omniverse Interfaces ==================== + _timeline: ClassVar[omni.timeline.ITimeline] = omni.timeline.get_timeline_interface() + _message_bus: ClassVar[carb.eventdispatcher.IEventDispatcher] = carb.eventdispatcher.get_eventdispatcher() + _physx_interface: ClassVar[omni.physx.IPhysx] = omni.physx.get_physx_interface() + _physx_sim_interface: ClassVar[omni.physx.IPhysxSimulation] = omni.physx.get_physx_simulation_interface() + _carb_settings: ClassVar[carb.settings.ISettings] = carb.settings.get_settings() + + # ==================== Simulation Views ==================== + _view: ClassVar[omni.physics.tensors.SimulationView | None] = None + _view_warp: ClassVar[omni.physics.tensors.SimulationView | None] = None + _backend: ClassVar[str] = "torch" + + # ==================== State Flags ==================== + _warmup_needed: ClassVar[bool] = True + _view_created: ClassVar[bool] = False + _assets_loaded: ClassVar[bool] = True + + # ==================== Physics Scenes ==================== + _physics_scene_apis: ClassVar[OrderedDict[str, PhysxSchema.PhysxSceneAPI]] = OrderedDict() + + # ==================== Callbacks ==================== + _callbacks: ClassVar[dict[int, Any]] = {} + _callback_id: ClassVar[int] = 0 + _handles: ClassVar[dict[str, Any]] = {} + + # ==================== Context & Configuration ==================== + _sim: ClassVar["SimulationContext | None"] = None + _cfg: ClassVar["PhysxManagerCfg | None"] = None + + # ==================== Device & Fabric ==================== + _physics_device: ClassVar[str] = "cpu" + _fabric_iface: ClassVar[Any] = None + _update_fabric: ClassVar[Callable[[float, float], None] | None] = None + _anim_recorder: ClassVar[AnimationRecorder | None] = None + + # Compatibility stub for Isaac Sim code that calls _simulation_manager_interface + class _PhysxManagerInterfaceStub: + """Minimal stub providing Isaac Sim compatibility interface.""" + + @staticmethod + def reset() -> None: + pass + + @staticmethod + def get_simulation_time() -> float: + try: + return omni.physx.get_physx_interface().get_simulation_time() + except Exception: + return 0.0 + + @staticmethod + def is_simulating() -> bool: + try: + return omni.physx.get_physx_interface().is_simulating() + except Exception: + return False + + def __getattr__(self, name: str) -> Callable[..., Any]: + """Return no-op callable for any undefined method.""" + return lambda *args, **kwargs: None + + _simulation_manager_interface = _PhysxManagerInterfaceStub() + + # ------------------------------------------------------------------ + # Public API + # ------------------------------------------------------------------ + + @classmethod + def initialize(cls, sim_context: "SimulationContext") -> None: + """Initialize the manager with simulation context and set up physics. + + Args: + sim_context: Parent simulation context (provides stage, carb_settings, logger). + """ + cls._sim = sim_context + # Store config reference for easy access + cls._cfg = sim_context.cfg.physics_manager_cfg # type: ignore[assignment] + cls._setup_callbacks() + cls._track_physics_scenes() + + # Configure physics settings + cls._configure_simulation_dt() + cls._apply_physics_settings() + + # a stage update here is needed for the case when physics_dt != rendering_dt + cls._sim.set_setting("/app/player/playSimulations", False) + omni.kit.app.get_app().update() + cls._sim.set_setting("/app/player/playSimulations", True) + + # load fabric interface + cls._load_fabric_interface() + + # initialize animation recorder + cls._anim_recorder = AnimationRecorder(cls._sim.carb_settings, omni.kit.app.get_app()) + + @classmethod + def reset(cls, soft: bool = False) -> None: + """Reset the physics simulation. + + Args: + soft: If True, skip full reinitialization. + """ + if not soft: + # initialize the physics simulation + if cls._view is None: + cls._initialize_physics() + + # app.update() may be changing the cuda device in reset, so we force it back to our desired device here + if "cuda" in cls._physics_device: + torch.cuda.set_device(cls._physics_device) + + # enable kinematic rendering with fabric + if cls._view is not None: + cls._view._backend.initialize_kinematic_bodies() + + @classmethod + def forward(cls) -> None: + """Update articulation kinematics and fabric for rendering.""" + if cls._fabric_iface is not None and cls._update_fabric is not None: + if cls._view is not None and cls._sim is not None and cls._sim.is_playing(): + # Update the articulations' link's poses before rendering + cls._view.update_articulations_kinematic() + cls._update_fabric(0.0, 0.0) + + @classmethod + def step(cls) -> None: + """Step the physics simulation (physics only, no rendering).""" + if cls._cfg is None: + return + + # update animation recorder if enabled + if cls._anim_recorder is not None and cls._anim_recorder.enabled and cls._anim_recorder.update(): + logger.warning("Animation recording finished. Closing app.") + omni.kit.app.get_app().shutdown() + return + + # step physics only + cls._physx_sim_interface.simulate(cls._cfg.dt, 0.0) + cls._physx_sim_interface.fetch_results() + + # physics step may change cuda device, force it back + if "cuda" in cls._physics_device: + torch.cuda.set_device(cls._physics_device) + + @classmethod + def close(cls) -> None: + """Clean up physics resources.""" + # clear the simulation manager state (notifies assets to cleanup) + cls._clear() + # detach the stage from physx + if cls._physx_sim_interface is not None: + cls._physx_sim_interface.detach_stage() + # clear references + cls._sim = None + cls._cfg = None + cls._anim_recorder = None + + @classmethod + def _clear(cls) -> None: + """Clear all state and callbacks (internal use only).""" + # Notify assets to clean up (PRIM_DELETION with "/" = clear all) + cls._message_bus.dispatch_event(IsaacEvents.PRIM_DELETION.value, payload={"prim_path": "/"}) + # Properly unsubscribe handles before clearing + # Timeline subscriptions are auto-cleaned by omni.timeline + # Message bus observers just need to be deleted + cls._handles.clear() + cls._callbacks.clear() + # Invalidate views before clearing + if cls._view: + cls._view.invalidate() + cls._view = None + if cls._view_warp: + cls._view_warp.invalidate() + cls._view_warp = None + # Reset state + cls._warmup_needed = True + cls._view_created = False + cls._assets_loaded = True + cls._physics_scene_apis.clear() + # Clear fabric interface + cls._fabric_iface = None + cls._update_fabric = None + + @classmethod + def _initialize_physics(cls) -> None: + """Warm-start physics and create simulation views (internal use only).""" + if not cls._warmup_needed: + return + cls._physx_interface.force_load_physics_from_usd() + cls._physx_interface.start_simulation() + cls._physx_interface.update_simulation(cls.get_physics_dt(), 0.0) + cls._physx_sim_interface.fetch_results() + cls._message_bus.dispatch_event(IsaacEvents.PHYSICS_WARMUP.value, payload={}) + cls._warmup_needed = False + cls._create_views() + + @classmethod + def get_physics_sim_view(cls) -> omni.physics.tensors.SimulationView | None: + """Get the physics simulation view.""" + return cls._view + + @classmethod + def get_physics_dt(cls) -> float: + """Get the physics timestep in seconds.""" + # Prefer config if available + if cls._cfg is not None: + return cls._cfg.dt + # Fallback to USD scene + if cls._physics_scene_apis: + api = list(cls._physics_scene_apis.values())[0] + hz = api.GetTimeStepsPerSecondAttr().Get() + return 1.0 / hz if hz else 0.0 + return 1.0 / 60.0 + + @classmethod + def get_device(cls) -> str: + """Get the physics simulation device (e.g., 'cuda:0' or 'cpu').""" + return cls._physics_device + + @classmethod + def _is_gpu_device(cls) -> bool: + """Check if configured for GPU physics.""" + return cls._sim is not None and "cuda" in cls._sim.device + + @classmethod + def is_fabric_enabled(cls) -> bool: + """Returns whether the fabric interface is enabled.""" + return cls._fabric_iface is not None + + @classmethod + def _set_physics_sim_device(cls, device: str) -> None: + """Set the physics simulation device (internal use only).""" + if "cuda" in device: + parts = device.split(":") + device_id = int(parts[1]) if len(parts) > 1 else max(0, cls._carb_settings.get_as_int("/physics/cudaDevice")) + cls._carb_settings.set_int("/physics/cudaDevice", device_id) + cls._carb_settings.set_bool("/physics/suppressReadback", True) + cls._set_gpu_dynamics(True) + cls._enable_fabric(True) + elif device == "cpu": + cls._carb_settings.set_bool("/physics/suppressReadback", False) + cls._set_gpu_dynamics(False) + else: + raise ValueError(f"Device must be 'cuda[:N]' or 'cpu', got '{device}'") + + @classmethod + def assets_loading(cls) -> bool: + """Check if assets are currently loading.""" + return not cls._assets_loaded + + # ------------------------------------------------------------------ + # Callback Registration + # ------------------------------------------------------------------ + + @classmethod + def register_callback(cls, callback: Callable, event: IsaacEvents, order: int = 0, name: str | None = None) -> int: + """Register a callback for a simulation event. + + Args: + callback: Function to call when event fires. + event: The event type to listen for. + order: Priority (lower = earlier). + name: Optional name for the callback. + + Returns: + Callback ID for deregistration. + """ + cid = cls._callback_id + cls._callback_id += 1 + + # Handle bound methods with weak references + if hasattr(callback, "__self__"): + obj_ref = weakref.proxy(callback.__self__) + method_name = callback.__name__ + + def cb(e: Any, o: Any = obj_ref, m: str = method_name) -> Any: + return getattr(o, m)(e) + else: + cb = callback + + if event in (IsaacEvents.PHYSICS_WARMUP, IsaacEvents.PHYSICS_READY, IsaacEvents.POST_RESET, + IsaacEvents.SIMULATION_VIEW_CREATED, IsaacEvents.PRIM_DELETION): + cls._callbacks[cid] = cls._message_bus.observe_event(event_name=event.value, order=order, on_event=cb) + + elif event == IsaacEvents.POST_PHYSICS_STEP: + cls._callbacks[cid] = cls._physx_interface.subscribe_physics_on_step_events( + lambda dt, c=cb: c(dt) if cls._view_created else None, pre_step=False, order=order + ) + + elif event == IsaacEvents.PRE_PHYSICS_STEP: + cls._callbacks[cid] = cls._physx_interface.subscribe_physics_on_step_events( + lambda dt, c=cb: c(dt) if cls._view_created else None, pre_step=True, order=order + ) + + elif event == IsaacEvents.TIMELINE_STOP: + cls._callbacks[cid] = cls._timeline.get_timeline_event_stream().create_subscription_to_pop_by_type( + int(omni.timeline.TimelineEventType.STOP), cb, order=order, name=name + ) + else: + raise ValueError(f"Unsupported event: {event}") + + return cid + + @classmethod + def deregister_callback(cls, callback_id: int) -> None: + """Deregister a callback.""" + cls._callbacks.pop(callback_id, None) + + @classmethod + def enable_stage_open_callback(cls, enable: bool) -> None: + """Enable or disable stage open tracking.""" + if enable and "stage_open" not in cls._handles: + cls._handles["stage_open"] = cls._message_bus.observe_event( + event_name=omni.usd.get_context().stage_event_name(omni.usd.StageEventType.OPENED), + on_event=cls._on_stage_open, + ) + elif not enable and "stage_open" in cls._handles: + del cls._handles["stage_open"] + cls._assets_loaded = True + + # ------------------------------------------------------------------ + # Internal + # ------------------------------------------------------------------ + + @classmethod + def _setup_callbacks(cls) -> None: + """Set up internal timeline callbacks.""" + # Guard against duplicate subscriptions + if "play" in cls._handles: + return + stream = cls._timeline.get_timeline_event_stream() + cls._handles["play"] = stream.create_subscription_to_pop_by_type( + int(omni.timeline.TimelineEventType.PLAY), cls._on_play + ) + cls._handles["stop"] = stream.create_subscription_to_pop_by_type( + int(omni.timeline.TimelineEventType.STOP), cls._on_stop + ) + cls.enable_stage_open_callback(True) + + @classmethod + def _on_play(cls, event: Any) -> None: + """Handle timeline play.""" + if cls._carb_settings.get_as_bool("/app/player/playSimulations"): + cls._initialize_physics() + + @classmethod + def _on_stop(cls, event: Any) -> None: + """Handle timeline stop.""" + cls._warmup_needed = True + if cls._view: + cls._view.invalidate() + cls._view = None + if cls._view_warp: + cls._view_warp.invalidate() + cls._view_warp = None + cls._view_created = False + + @classmethod + def _on_stage_open(cls, event: Any) -> None: + """Handle stage open.""" + cls._physics_scene_apis.clear() + cls._callbacks.clear() + cls._track_physics_scenes() + cls._assets_loaded = True + + def on_loading(e): + cls._assets_loaded = False + + def on_loaded(e): + cls._assets_loaded = True + + ctx = omni.usd.get_context() + cls._handles["assets_loading"] = cls._message_bus.observe_event( + event_name=ctx.stage_event_name(omni.usd.StageEventType.ASSETS_LOADING), on_event=on_loading + ) + cls._handles["assets_loaded"] = cls._message_bus.observe_event( + event_name=ctx.stage_event_name(omni.usd.StageEventType.ASSETS_LOADED), on_event=on_loaded + ) + + @classmethod + def _create_views(cls) -> None: + """Create physics simulation views.""" + if cls._view_created: + return + + from isaaclab.sim.utils.stage import get_current_stage_id + + stage_id = get_current_stage_id() + cls._view = omni.physics.tensors.create_simulation_view(cls._backend, stage_id=stage_id) + cls._view_warp = omni.physics.tensors.create_simulation_view("warp", stage_id=stage_id) + if cls._view is not None: + cls._view.set_subspace_roots("/") + if cls._view_warp is not None: + cls._view_warp.set_subspace_roots("/") + + cls._physx_interface.update_simulation(cls.get_physics_dt(), 0.0) + cls._view_created = True + cls._message_bus.dispatch_event(IsaacEvents.SIMULATION_VIEW_CREATED.value, payload={}) + cls._message_bus.dispatch_event(IsaacEvents.PHYSICS_READY.value, payload={}) + + @classmethod + def _track_physics_scenes(cls) -> None: + """Scan stage for physics scenes.""" + stage = omni.usd.get_context().get_stage() + if stage: + for prim in stage.Traverse(): + if prim.GetTypeName() == "PhysicsScene": + cls._physics_scene_apis[prim.GetPath().pathString] = PhysxSchema.PhysxSceneAPI.Apply(prim) + + @classmethod + def _set_gpu_dynamics(cls, enable: bool) -> None: + """Enable/disable GPU dynamics on all physics scenes.""" + bp_type = "GPU" if enable else "MBP" + for api in cls._physics_scene_apis.values(): + if not api.GetPrim().IsValid(): + continue + if api.GetBroadphaseTypeAttr().Get() is None: + api.CreateBroadphaseTypeAttr(bp_type) + else: + api.GetBroadphaseTypeAttr().Set(bp_type) + if api.GetEnableGPUDynamicsAttr().Get() is None: + api.CreateEnableGPUDynamicsAttr(enable) + else: + api.GetEnableGPUDynamicsAttr().Set(enable) + + @classmethod + def _enable_fabric(cls, enable: bool) -> None: + """Enable/disable physics fabric.""" + mgr = omni.kit.app.get_app().get_extension_manager() + was_enabled = mgr.is_extension_enabled("omni.physx.fabric") + if enable and not was_enabled: + mgr.set_extension_enabled_immediate("omni.physx.fabric", True) + elif not enable and was_enabled: + mgr.set_extension_enabled_immediate("omni.physx.fabric", False) + cls._carb_settings.set_bool("/physics/updateToUsd", not enable) + cls._carb_settings.set_bool("/physics/updateParticlesToUsd", not enable) + cls._carb_settings.set_bool("/physics/updateVelocitiesToUsd", not enable) + cls._carb_settings.set_bool("/physics/updateForceSensorsToUsd", not enable) + + # ------------------------------------------------------------------ + # Physics Configuration (from PhysXBackend) + # ------------------------------------------------------------------ + + @classmethod + def _configure_simulation_dt(cls) -> None: + """Configures the physics simulation step size.""" + if cls._sim is None or cls._cfg is None: + return + + carb_settings = cls._sim.carb_settings + + # Get physics scene API from the physics interface + stage = cls._sim.stage + physics_scene_prim = stage.GetPrimAtPath(cls._cfg.physics_prim_path) + physx_scene_api = PhysxSchema.PhysxSceneAPI(physics_scene_prim) + + # if rendering is called the substeps term is used to determine + # how many physics steps to perform per rendering step. + # it is not used if step(render=False). + render_interval = max(cls._sim.cfg.render_interval, 1) + + # set simulation step per second + steps_per_second = int(1.0 / cls._cfg.dt) + physx_scene_api.CreateTimeStepsPerSecondAttr(steps_per_second) + # set minimum number of steps per frame + min_steps = int(steps_per_second / render_interval) + carb_settings.set_int("/persistent/simulation/minFrameRate", min_steps) + + @classmethod + def _apply_physics_settings(cls) -> None: + """Apply all physics configuration settings.""" + if cls._sim is None or cls._cfg is None: + return + + cls._apply_carb_settings() + cls._apply_device_settings() + cls._create_default_material() + cls._apply_physx_scene_settings() + cls._log_config_warnings() + + @classmethod + def _apply_carb_settings(cls) -> None: + """Apply Carbonite physics settings.""" + if cls._sim is None: + return + settings = cls._sim.carb_settings + + # Enable hydra scene-graph instancing for GUI rendering + settings.set_bool("/persistent/omnihydra/useSceneGraphInstancing", True) + # Use PhysX SDK dispatcher instead of carb tasking + settings.set_bool("/physics/physxDispatcher", True) + # Disable contact processing by default (enabled when contact sensors are created) + settings.set_bool("/physics/disableContactProcessing", True) + # Enable contact reporting for cylinder/cone shapes (not natively supported by PhysX) + settings.set_bool("/physics/collisionConeCustomGeometry", False) + settings.set_bool("/physics/collisionCylinderCustomGeometry", False) + # Hide simulation output window + settings.set_bool("/physics/autoPopupSimulationOutputWindow", False) + + @classmethod + def _apply_device_settings(cls) -> None: + """Configure GPU/CPU device settings based on SimulationContext.device.""" + if cls._sim is None: + return + settings = cls._sim.carb_settings + device = cls._sim.device # Device comes from SimulationContext + + if cls._is_gpu_device(): + device_parts = device.split(":") + if len(device_parts) == 1: + # "cuda" without ID - use carb setting or default to 0 + device_id = max(0, settings.get_as_int("/physics/cudaDevice")) + else: + device_id = int(device_parts[1]) + + settings.set_int("/physics/cudaDevice", device_id) + settings.set_bool("/physics/suppressReadback", True) + cls._physics_device = f"cuda:{device_id}" + else: + settings.set_int("/physics/cudaDevice", -1) + settings.set_bool("/physics/suppressReadback", False) + cls._physics_device = "cpu" + + cls._backend = "torch" + cls._set_physics_sim_device(cls._physics_device) + + @classmethod + def _create_default_material(cls) -> None: + """Create and bind default physics material if configured.""" + if cls._cfg is None or cls._cfg.physics_material is None: + return + + material_path = f"{cls._cfg.physics_prim_path}/defaultMaterial" + cls._cfg.physics_material.func(material_path, cls._cfg.physics_material) + sim_utils.bind_physics_material(cls._cfg.physics_prim_path, material_path) + + @classmethod + def _apply_physx_scene_settings(cls) -> None: + """Apply PhysX scene API settings.""" + if cls._sim is None or cls._cfg is None: + return + + stage = cls._sim.stage + physics_scene_prim = stage.GetPrimAtPath(cls._cfg.physics_prim_path) + physx_scene_api = PhysxSchema.PhysxSceneAPI(physics_scene_prim) + + is_gpu = cls._is_gpu_device() + + # Broadphase and GPU dynamics + physx_scene_api.CreateBroadphaseTypeAttr("GPU" if is_gpu else "MBP") + physx_scene_api.CreateEnableGPUDynamicsAttr(is_gpu) + + # CCD (disabled for GPU dynamics) + enable_ccd = cls._cfg.enable_ccd + if is_gpu and enable_ccd: + enable_ccd = False + cls._sim.logger.warning( + "CCD is disabled when GPU dynamics is enabled. Disable CCD in PhysxManagerCfg to suppress this warning." + ) + physx_scene_api.CreateEnableCCDAttr(enable_ccd) + + # Solver type + solver_type = "PGS" if cls._cfg.solver_type == 0 else "TGS" + physx_scene_api.CreateSolverTypeAttr(solver_type) + + # Articulation contact ordering + attr = physx_scene_api.GetPrim().CreateAttribute( + "physxScene:solveArticulationContactLast", Sdf.ValueTypeNames.Bool + ) + attr.Set(cls._cfg.solve_articulation_contact_last) + + # Apply remaining settings from config + skip_keys = { + "solver_type", "enable_ccd", "solve_articulation_contact_last", + "dt", "device", "render_interval", "gravity", + "physics_prim_path", "use_fabric", "physics_material" + } + for key, value in cls._cfg.to_dict().items(): # type: ignore + if key in skip_keys: + continue + if key == "bounce_threshold_velocity": + key = "bounce_threshold" + sim_utils.safe_set_attribute_on_usd_schema(physx_scene_api, key, value, camel_case=True) + + @classmethod + def _log_config_warnings(cls) -> None: + """Log helpful configuration warnings.""" + if cls._cfg is None or cls._sim is None: + return + + if cls._cfg.solver_type == 1 and not cls._cfg.enable_external_forces_every_iteration: + logger.warning( + "enable_external_forces_every_iteration is False with TGS solver. " + "If experiencing noisy velocities, enable this flag and increase velocity iterations to 1-2." + ) + + if not cls._cfg.enable_stabilization and cls._cfg.dt > 0.0333: + cls._sim.logger.warning( + "Large timestep (>0.0333s) without stabilization may cause physics issues. " + "Consider enabling enable_stabilization or reducing dt." + ) + + @classmethod + def _load_fabric_interface(cls) -> None: + """Loads the fabric interface if enabled.""" + if cls._sim is None or cls._cfg is None: + return + + carb_settings = cls._sim.carb_settings + + extension_manager = omni.kit.app.get_app().get_extension_manager() + fabric_enabled = extension_manager.is_extension_enabled("omni.physx.fabric") + + if cls._cfg.use_fabric: + if not fabric_enabled: + extension_manager.set_extension_enabled_immediate("omni.physx.fabric", True) + + # load fabric interface + from omni.physxfabric import get_physx_fabric_interface + + # acquire fabric interface + cls._fabric_iface = get_physx_fabric_interface() + if hasattr(cls._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. + cls._update_fabric = cls._fabric_iface.force_update + else: + # Needed for backward compatibility with older Isaac Sim versions + cls._update_fabric = cls._fabric_iface.update + else: + if fabric_enabled: + extension_manager.set_extension_enabled_immediate("omni.physx.fabric", False) + # set fabric interface to None + cls._fabric_iface = None + + # set carb settings for fabric + carb_settings.set_bool("/isaaclab/physics/fabric_enabled", cls._cfg.use_fabric) + carb_settings.set_bool("/physics/updateToUsd", not cls._cfg.use_fabric) + carb_settings.set_bool("/physics/updateParticlesToUsd", not cls._cfg.use_fabric) + carb_settings.set_bool("/physics/updateVelocitiesToUsd", not cls._cfg.use_fabric) + carb_settings.set_bool("/physics/updateForceSensorsToUsd", not cls._cfg.use_fabric) + carb_settings.set_bool("/physics/updateResidualsToUsd", not cls._cfg.use_fabric) + # disable simulation output window visibility + carb_settings.set_bool("/physics/visualizationDisplaySimulationOutput", False) diff --git a/source/isaaclab/isaaclab/physics/physx_manager_cfg.py b/source/isaaclab/isaaclab/physics/physx_manager_cfg.py new file mode 100644 index 00000000000..55dbd179f21 --- /dev/null +++ b/source/isaaclab/isaaclab/physics/physx_manager_cfg.py @@ -0,0 +1,244 @@ +# 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 .physics_manager_cfg import PhysicsManagerCfg + +if TYPE_CHECKING: + from .physics_manager import PhysicsManager + from isaaclab.sim.spawners.materials import RigidBodyMaterialCfg + + +@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 + # ------------------------------------------------------------------ + + 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. + """ + + physics_material: "RigidBodyMaterialCfg | None" = None + """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``. + """ + + # ------------------------------------------------------------------ + # 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.""" + + # ------------------------------------------------------------------ + # Factory Method + # ------------------------------------------------------------------ + + def create_manager(self) -> type["PhysicsManager"]: + """Create and return the PhysxManager class. + + Returns: + The PhysxManager class. + """ + from .physx_manager import PhysxManager + return PhysxManager diff --git a/source/isaaclab/isaaclab/sensors/contact_sensor/contact_sensor.py b/source/isaaclab/isaaclab/sensors/contact_sensor/contact_sensor.py index 3a3f4d5c2e9..dc4081b25ad 100644 --- a/source/isaaclab/isaaclab/sensors/contact_sensor/contact_sensor.py +++ b/source/isaaclab/isaaclab/sensors/contact_sensor/contact_sensor.py @@ -14,7 +14,7 @@ import carb import omni.physics.tensors.impl.api as physx -from isaacsim.core.simulation_manager import SimulationManager +from isaaclab.physics.physx_manager import PhysxManager from pxr import PhysxSchema import isaaclab.sim as sim_utils @@ -256,7 +256,7 @@ def compute_first_air(self, dt: float, abs_tol: float = 1.0e-8) -> torch.Tensor: def _initialize_impl(self): super()._initialize_impl() # obtain global simulation view - self._physics_sim_view = SimulationManager.get_physics_sim_view() + self._physics_sim_view = PhysxManager.get_physics_sim_view() # check that only rigid bodies are selected leaf_pattern = self.cfg.prim_path.rsplit("/", 1)[-1] template_prim_path = self._parent_prims[0].GetPath().pathString diff --git a/source/isaaclab/isaaclab/sensors/frame_transformer/frame_transformer.py b/source/isaaclab/isaaclab/sensors/frame_transformer/frame_transformer.py index 50f75b565e1..9ec17337a06 100644 --- a/source/isaaclab/isaaclab/sensors/frame_transformer/frame_transformer.py +++ b/source/isaaclab/isaaclab/sensors/frame_transformer/frame_transformer.py @@ -11,7 +11,7 @@ from collections.abc import Sequence from typing import TYPE_CHECKING -from isaacsim.core.simulation_manager import SimulationManager +from isaaclab.physics.physx_manager import PhysxManager from pxr import UsdPhysics import isaaclab.sim as sim_utils @@ -249,7 +249,7 @@ def _initialize_impl(self): body_names_regex = [tracked_prim_path.replace("env_0", "env_*") for tracked_prim_path in tracked_prim_paths] # obtain global simulation view - self._physics_sim_view = SimulationManager.get_physics_sim_view() + self._physics_sim_view = PhysxManager.get_physics_sim_view() # Create a prim view for all frames and initialize it # order of transforms coming out of view will be source frame followed by target frame(s) self._frame_physx_view = self._physics_sim_view.create_rigid_body_view(body_names_regex) diff --git a/source/isaaclab/isaaclab/sensors/imu/imu.py b/source/isaaclab/isaaclab/sensors/imu/imu.py index 1cf0dda12b1..fdc9a9a8452 100644 --- a/source/isaaclab/isaaclab/sensors/imu/imu.py +++ b/source/isaaclab/isaaclab/sensors/imu/imu.py @@ -9,7 +9,7 @@ from collections.abc import Sequence from typing import TYPE_CHECKING -from isaacsim.core.simulation_manager import SimulationManager +from isaaclab.physics.physx_manager import PhysxManager from pxr import UsdGeom, UsdPhysics import isaaclab.sim as sim_utils @@ -135,7 +135,7 @@ def _initialize_impl(self): # Initialize parent class super()._initialize_impl() # obtain global simulation view - self._physics_sim_view = SimulationManager.get_physics_sim_view() + self._physics_sim_view = PhysxManager.get_physics_sim_view() # check if the prim at path is a rigid prim prim = sim_utils.find_first_matching_prim(self.cfg.prim_path) if prim is None: diff --git a/source/isaaclab/isaaclab/sensors/ray_caster/ray_caster.py b/source/isaaclab/isaaclab/sensors/ray_caster/ray_caster.py index d7aa07419d4..5bf4ca99af7 100644 --- a/source/isaaclab/isaaclab/sensors/ray_caster/ray_caster.py +++ b/source/isaaclab/isaaclab/sensors/ray_caster/ray_caster.py @@ -14,7 +14,7 @@ from typing import TYPE_CHECKING, ClassVar import omni -from isaacsim.core.simulation_manager import SimulationManager +from isaaclab.physics.physx_manager import PhysxManager from pxr import UsdGeom, UsdPhysics import isaaclab.sim as sim_utils @@ -143,7 +143,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 = PhysxManager.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 7de0c82541a..0d03e619910 100644 --- a/source/isaaclab/isaaclab/sensors/sensor_base.py +++ b/source/isaaclab/isaaclab/sensors/sensor_base.py @@ -22,7 +22,7 @@ import omni.kit.app import omni.timeline -from isaacsim.core.simulation_manager import IsaacEvents, SimulationManager +from isaaclab.sim import IsaacEvents, PhysxManager import isaaclab.sim as sim_utils from isaaclab.sim.utils.stage import get_current_stage @@ -203,7 +203,6 @@ def _initialize_impl(self): raise RuntimeError("Simulation Context is not initialized!") # Obtain device and backend self._device = sim.device - self._backend = sim.backend self._sim_physics_dt = sim.get_physics_dt() # Count number of environments env_prim_path_expr = self.cfg.prim_path.rsplit("/", 1)[0] @@ -285,7 +284,7 @@ def safe_callback(callback_name, event, obj_ref): order=10, ) # register prim deletion callback - self._prim_deletion_callback_id = SimulationManager.register_callback( + self._prim_deletion_callback_id = PhysxManager.register_callback( lambda event, obj_ref=obj_ref: safe_callback("_on_prim_deletion", event, obj_ref), event=IsaacEvents.PRIM_DELETION, ) @@ -301,8 +300,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 + if builtins.ISAACLAB_CALLBACK_EXCEPTION is None: # type: ignore + builtins.ISAACLAB_CALLBACK_EXCEPTION = e # type: ignore self._is_initialized = True def _invalidate_initialize_callback(self, event): @@ -312,15 +311,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: This function is called when the prim is deleted. """ + prim_path = event.payload["prim_path"] if prim_path == "/": self._clear_callbacks() return @@ -333,7 +333,7 @@ def _on_prim_deletion(self, prim_path: str) -> None: def _clear_callbacks(self) -> None: """Clears the callbacks.""" if self._prim_deletion_callback_id: - SimulationManager.deregister_callback(self._prim_deletion_callback_id) + PhysxManager.deregister_callback(self._prim_deletion_callback_id) self._prim_deletion_callback_id = None if self._initialize_handle: self._initialize_handle.unsubscribe() diff --git a/source/isaaclab/isaaclab/sim/__init__.py b/source/isaaclab/isaaclab/sim/__init__.py index 1dc920f4e10..d4ed0865e40 100644 --- a/source/isaaclab/isaaclab/sim/__init__.py +++ b/source/isaaclab/isaaclab/sim/__init__.py @@ -28,8 +28,30 @@ 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 isaaclab.physics.physx_manager import PhysxManager, IsaacEvents # noqa: F401, F403 from .spawners import * # noqa: F401, F403 from .utils import * # noqa: F401, F403 from .views import * # noqa: F401, F403 + +# Monkey-patch Isaac Sim's PhysxManager to use Isaac Lab's implementation +# This ensures all code (including Isaac Sim internals) uses our manager +try: + import isaacsim.core.simulation_manager as _isaacsim_sim_manager + import isaacsim.core.simulation_manager.impl.simulation_manager as _isaacsim_sim_manager_impl + + # Get reference to the ORIGINAL Isaac Sim SimulationManager before patching + _OriginalSimManager = _isaacsim_sim_manager_impl.SimulationManager + + # Disable all default callbacks from Isaac Sim's manager to prevent double-dispatch + # These callbacks were already set up when the extension loaded, so we need to disable them + _OriginalSimManager.enable_all_default_callbacks(False) + + # Replace the class in both the module and impl module + _isaacsim_sim_manager.PhysxManager = PhysxManager + _isaacsim_sim_manager.IsaacEvents = IsaacEvents + _isaacsim_sim_manager_impl.SimulationManager = PhysxManager + _isaacsim_sim_manager_impl.IsaacEvents = IsaacEvents +except ImportError: + pass # Isaac Sim extension not loaded yet, will be patched when available diff --git a/source/isaaclab/isaaclab/sim/interface/__init__.py b/source/isaaclab/isaaclab/sim/interface/__init__.py new file mode 100644 index 00000000000..a681cdc219b --- /dev/null +++ b/source/isaaclab/isaaclab/sim/interface/__init__.py @@ -0,0 +1,9 @@ +from .interface import Interface +from .physics_interface import PhysicsInterface +from .visualizer_interface import VisualizerInterface + +__all__ = [ + "Interface", + "PhysicsInterface", + "VisualizerInterface", +] \ No newline at end of file diff --git a/source/isaaclab/isaaclab/sim/interface/interface.py b/source/isaaclab/isaaclab/sim/interface/interface.py new file mode 100644 index 00000000000..ae4bc8afdb1 --- /dev/null +++ b/source/isaaclab/isaaclab/sim/interface/interface.py @@ -0,0 +1,69 @@ +# 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 interface class for SimulationContext subsystems.""" + +from __future__ import annotations + +from abc import ABC, abstractmethod +from typing import TYPE_CHECKING + +if TYPE_CHECKING: + from .simulation_context import SimulationContext + + +class Interface(ABC): + """Base class for simulation subsystem interfaces. + + Provides a common lifecycle: __init__() -> reset() -> step()/forward() (repeated) -> close() + """ + + def __init__(self, sim_context: "SimulationContext"): + """Initialize interface with simulation context. + + Args: + sim_context: Parent simulation context. + """ + self._sim = sim_context + + @abstractmethod + def reset(self, soft: bool = False) -> None: + """Reset the subsystem. + + Args: + soft: If True, skip full reinitialization. + """ + pass + + @abstractmethod + def forward(self) -> None: + """Update state without stepping simulation.""" + pass + + @abstractmethod + def step(self, render: bool = True) -> None: + """Step the subsystem by one timestep. + + Args: + render: Whether to render after stepping. Defaults to True. + """ + pass + + @abstractmethod + def close(self) -> None: + """Clean up resources.""" + pass + + def play(self) -> None: + """Handle simulation start.""" + pass + + def pause(self) -> None: + """Handle simulation pause.""" + pass + + def stop(self) -> None: + """Handle simulation stop.""" + pass diff --git a/source/isaaclab/isaaclab/sim/interface/physics_interface.py b/source/isaaclab/isaaclab/sim/interface/physics_interface.py new file mode 100644 index 00000000000..3e55b8b4ad1 --- /dev/null +++ b/source/isaaclab/isaaclab/sim/interface/physics_interface.py @@ -0,0 +1,135 @@ +# 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 + +"""Physics interface for SimulationContext.""" + +from __future__ import annotations + +import logging +from typing import TYPE_CHECKING + +import torch +from pxr import Gf, UsdGeom, UsdPhysics + +import isaaclab.sim as sim_utils +from isaaclab.physics.physics_manager import PhysicsManager +from .interface import Interface + +if TYPE_CHECKING: + from .simulation_context import SimulationContext + +logger = logging.getLogger(__name__) + + +class PhysicsInterface(Interface): + """Manages USD physics scene and delegates to PhysicsManager. + + This interface handles: + - USD physics scene creation and configuration + - Gravity, timestep, and unit settings + - Delegating lifecycle operations to the physics manager + """ + + def __init__(self, sim_context: "SimulationContext"): + """Initialize physics scene and physics manager. + + Args: + sim_context: Parent simulation context. + """ + super().__init__(sim_context) + + # Get config reference + self._cfg = self._sim.cfg.physics_manager_cfg + self.physics_prim_path = self._cfg.physics_prim_path + self.backend = "torch" + + # Get the physics manager class from config + self.physics_manager: type[PhysicsManager] = self._cfg.create_manager() + + # Initialize USD physics scene + self._init_usd_physics_scene() + # Initialize the physics manager + self.physics_manager.initialize(sim_context) + + @property + def physics_dt(self) -> float: + """Physics timestep.""" + return self.physics_manager.get_physics_dt() + + @property + def rendering_dt(self) -> float: + """Rendering timestep.""" + return self._cfg.dt * self._cfg.render_interval + + @property + def device(self) -> str: + """Device used for physics simulation.""" + return self.physics_manager.get_device() + + @property + def physics_sim_view(self): + """Physics simulation view with torch backend.""" + return self.physics_manager.get_physics_sim_view() + + def is_fabric_enabled(self) -> bool: + """Returns whether the fabric interface is enabled.""" + return self.physics_manager.is_fabric_enabled() + + def _init_usd_physics_scene(self) -> None: + """Create and configure the USD physics scene.""" + stage = self._sim.stage + with sim_utils.use_stage(stage): + # Set stage conventions for metric units + UsdGeom.SetStageUpAxis(stage, "Z") + UsdGeom.SetStageMetersPerUnit(stage, 1.0) + UsdPhysics.SetStageKilogramsPerUnit(stage, 1.0) + + # Find and delete any existing physics scene + for prim in stage.Traverse(): + if prim.GetTypeName() == "PhysicsScene": + sim_utils.delete_prim(prim.GetPath().pathString, stage=stage) + + # Create a new physics scene + if stage.GetPrimAtPath(self._cfg.physics_prim_path).IsValid(): + raise RuntimeError(f"A prim already exists at path '{self._cfg.physics_prim_path}'.") + + physics_scene = UsdPhysics.Scene.Define(stage, self._cfg.physics_prim_path) + + # Pre-create gravity tensor to avoid torch heap corruption issues (torch 2.1+) + gravity = torch.tensor(self._cfg.gravity, dtype=torch.float32, device=self._cfg.device) + gravity_magnitude = torch.norm(gravity).item() + + # Avoid division by zero + if gravity_magnitude == 0.0: + gravity_direction = [0.0, 0.0, -1.0] + else: + gravity_direction = (gravity / gravity_magnitude).tolist() + + physics_scene.CreateGravityDirectionAttr(Gf.Vec3f(*gravity_direction)) + physics_scene.CreateGravityMagnitudeAttr(gravity_magnitude) + + def reset(self, soft: bool = False) -> None: + """Reset physics simulation. + + Args: + soft: If True, skip full reinitialization. + """ + self.physics_manager.reset(soft) + + def forward(self) -> None: + """Update articulation kinematics for rendering.""" + self.physics_manager.forward() + + def step(self, render: bool = True) -> None: + """Step physics simulation (physics only). + + Args: + render: Unused, kept for interface compatibility. + """ + self.physics_manager.step() + + def close(self) -> None: + """Clean up physics resources.""" + self.physics_manager.close() diff --git a/source/isaaclab/isaaclab/sim/interface/visualizer_interface.py b/source/isaaclab/isaaclab/sim/interface/visualizer_interface.py new file mode 100644 index 00000000000..3d051416d87 --- /dev/null +++ b/source/isaaclab/isaaclab/sim/interface/visualizer_interface.py @@ -0,0 +1,255 @@ +# 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 interface for SimulationContext.""" + +from __future__ import annotations + +import logging +from typing import TYPE_CHECKING + +from isaaclab.visualizers import Visualizer + +from .interface import Interface +from isaaclab.visualizers.physx_ov_visualizer_cfg import PhysxOVVisualizerCfg + +if TYPE_CHECKING: + from .simulation_context import SimulationContext + +logger = logging.getLogger(__name__) + + +class VisualizerInterface(Interface): + """Manages visualizer lifecycle and rendering for SimulationContext.""" + + def __init__(self, sim_context: "SimulationContext"): + """Initialize visualizer interface. + + Args: + sim_context: Parent simulation context. + """ + super().__init__(sim_context) + self.dt = self._sim.cfg.physics_manager_cfg.dt * self._sim.cfg.render_interval + + # Visualizer state + visualizers = "omniverse" + self._visualizers_str = [v.strip() for v in visualizers.split(",") if v.strip()] + self._visualizers: list[Visualizer] = [] + self._visualizer_step_counter = 0 + self._scene_data_provider: SceneDataProvider | None = None + self._was_playing = False + + # Initialize visualizers immediately + self.initialize_visualizers() + + # -- Properties -- + + @property + def settings(self): + return self._sim.carb_settings + + @property + def device(self) -> str: + return self._sim.device + + @property + def stage(self): + return self._sim.stage + + @property + def visualizers(self) -> list[Visualizer]: + return self._visualizers + + @property + def scene_data_provider(self) -> SceneDataProvider | None: + return self._scene_data_provider + + # -- Visualizer Initialization -- + + def _create_default_visualizer_configs(self, requested: list[str]) -> list: + """Create default configs for requested visualizer types.""" + configs = [] + type_map = {"omniverse": PhysxOVVisualizerCfg} + + for viz_type in requested: + if viz_type in type_map: + try: + configs.append(type_map[viz_type]()) + except Exception as e: + logger.error(f"Failed to create default config for '{viz_type}': {e}") + else: + logger.warning(f"Unknown visualizer type '{viz_type}'. Valid: {list(type_map.keys())}") + + return configs + + def initialize_visualizers(self) -> None: + """Initialize visualizers based on --visualizer flag.""" + if not self._visualizers_str: + if bool(self.settings.get("/isaaclab/visualizer")) or bool(self.settings.get("/isaaclab/render/offscreen")): + logger.info("No visualizers specified via --visualizer flag.") + return + + # Get or create visualizer configs + cfg_list = self._sim.cfg.visualizer_cfgs + if cfg_list is None: + visualizer_cfgs = self._create_default_visualizer_configs(self._visualizers_str) + else: + visualizer_cfgs = cfg_list if isinstance(cfg_list, list) else [cfg_list] + visualizer_cfgs = [c for c in visualizer_cfgs if c.visualizer_type in self._visualizers_str] + + if not visualizer_cfgs: + logger.info(f"Creating default configs for: {self._visualizers_str}") + visualizer_cfgs = self._create_default_visualizer_configs(self._visualizers_str) + + if not visualizer_cfgs: + return + + # Create scene data provider + self._scene_data_provider = None # SceneDataProvider(visualizer_cfgs) + + # Initialize each visualizer + for cfg in visualizer_cfgs: + try: + visualizer = cfg.create_visualizer() + scene_data = self._build_scene_data(cfg) + visualizer.initialize(scene_data) + self._visualizers.append(visualizer) + logger.info(f"Initialized: {type(visualizer).__name__} ({cfg.visualizer_type})") + except Exception as e: + logger.error(f"Failed to init '{cfg.visualizer_type}': {e}") + + def _build_scene_data(self, cfg) -> dict: + """Build scene data dict for visualizer initialization.""" + if cfg.visualizer_type in ("newton", "rerun"): + return {"scene_data_provider": self._scene_data_provider} + elif cfg.visualizer_type == "omniverse": + return {"usd_stage": self._sim.stage, "simulation_context": self._sim} + return {} + + # -- Unified Interface Methods -- + + def is_playing(self) -> bool: + """Check whether the simulation is playing.""" + for viz in self.visualizers: + return viz.is_running() + return True # physics is always playing when there is no visualizer, basically headless mode + + def is_stopped(self) -> bool: + """Check whether the simulation is stopped (not paused).""" + for viz in self.visualizers: + return viz.is_stopped() + return False + + def forward(self) -> None: + """Sync scene data and step all active visualizers. + + Args: + dt: Time step in seconds (0.0 for kinematics-only). + """ + if self._scene_data_provider: + self._scene_data_provider.update() + + if not self._visualizers: + return + + def step(self, render: bool = True) -> None: + """Step visualizers and optionally render. + + Args: + render: Whether to render after stepping. + """ + # If paused, keep rendering until playing or stopped + while not self.is_playing() and not self.is_stopped(): + self.render() + self._was_playing = False + + # Detect transition: was not playing → now playing (resume from pause) + is_playing = self.is_playing() + if not self._was_playing and is_playing: + self.reset(soft=True) + + # Update state tracking + self._was_playing = is_playing + + self.forward() + + if render: + self.render() + + def reset(self, soft: bool) -> None: + """Reset visualizers (warmup renders on hard reset).""" + for viz in self._visualizers: + viz.reset(soft) + + def close(self) -> None: + """Close all visualizers and clean up.""" + for viz in self._visualizers: + try: + viz.close() + except Exception as e: + logger.error(f"Error closing {type(viz).__name__}: {e}") + + self._visualizers.clear() + logger.info("All visualizers closed") + + def play(self) -> None: + """Handle simulation start.""" + for viz in self._visualizers: + viz.play() + + def stop(self) -> None: + """Handle simulation stop.""" + for viz in self._visualizers: + viz.stop() + + def pause(self) -> None: + """Pause the simulation.""" + for viz in self._visualizers: + viz.pause() + + def render(self) -> None: + """Render the scene. + + Args: + mode: Render mode to set, or None to keep current. + """ + self._visualizer_step_counter += 1 + to_remove = [] + + for viz in self._visualizers: + try: + if not viz.is_running(): + to_remove.append(viz) + continue + + # Block while training paused + while viz.is_training_paused() and viz.is_running(): + viz.step(0.0, state=None) + + viz.step(self.get_rendering_dt() or self.dt, state=None) + except Exception as e: + logger.error(f"Error stepping {type(viz).__name__}: {e}") + to_remove.append(viz) + + for viz in to_remove: + try: + viz.close() + self._visualizers.remove(viz) + logger.info(f"Removed: {type(viz).__name__}") + except Exception as e: + logger.error(f"Error closing visualizer: {e}") + + def get_rendering_dt(self) -> float: + """Get rendering dt from visualizers, or fall back to physics dt.""" + for viz in self._visualizers: + dt = viz.get_rendering_dt() + if dt is not None: + return dt + return self.dt + + 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) diff --git a/source/isaaclab/isaaclab/sim/simulation_cfg.py b/source/isaaclab/isaaclab/sim/simulation_cfg.py index 9f74b5ba016..be5a2576134 100644 --- a/source/isaaclab/isaaclab/sim/simulation_cfg.py +++ b/source/isaaclab/isaaclab/sim/simulation_cfg.py @@ -9,189 +9,14 @@ 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) - """ - - 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.""" - - 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. - - """ +from isaaclab.physics.physics_manager_cfg import PhysicsManagerCfg +from isaaclab.physics.physx_manager_cfg import PhysxManagerCfg +from isaaclab.visualizers import VisualizerCfg @configclass @@ -343,9 +168,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"``. @@ -356,18 +178,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. @@ -383,29 +196,13 @@ 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. + physics_manager_cfg: PhysicsManagerCfg = PhysxManagerCfg() + """Physics manager configuration. Default is PhysxManagerCfg(). - 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. + This configuration determines which physics manager to use. Override with + a different config (e.g., NewtonManagerCfg) to use a different physics backend. """ - physx: PhysxCfg = PhysxCfg() - """PhysX solver settings. Default is PhysxCfg().""" - physics_material: RigidBodyMaterialCfg = RigidBodyMaterialCfg() """Default physics material settings for rigid bodies. Default is RigidBodyMaterialCfg(). @@ -436,3 +233,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 e27053f1362..0809535f37d 100644 --- a/source/isaaclab/isaaclab/sim/simulation_context.py +++ b/source/isaaclab/isaaclab/sim/simulation_context.py @@ -4,1021 +4,264 @@ # SPDX-License-Identifier: BSD-3-Clause import builtins -import enum -import flatdict -import glob +import gc import logging -import numpy as np -import os -import re -import time -import toml -import torch import traceback -import weakref from collections.abc import Iterator from contextlib import contextmanager -from datetime import datetime from typing import Any 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 +from pxr import Usd, UsdUtils + +import isaaclab.sim.utils.stage as stage_utils import isaaclab.sim as sim_utils -from isaaclab.utils.logger import configure_logging +from isaaclab.sim.utils import create_new_stage_in_memory, raise_callback_exception_if_any from isaaclab.utils.version import get_isaac_sim_version - +from .interface import PhysicsInterface, VisualizerInterface, Interface 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. - - The simulation context helps control various simulation aspects. This includes: - - * 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. - - 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. - - 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. - - The simulation context can be used in two different modes of operations: - - 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. - - 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. - """ - - 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. +class SettingsHelper: + """Helper for typed Carbonite settings access.""" - 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: + def __init__(self, settings: "carb.settings.ISettings"): + self._settings = settings - * :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.""" - - def __init__(self, cfg: SimulationCfg | None = None): - """Creates a simulation context to control the simulator. + def set(self, name: str, value: Any) -> None: + """Set a Carbonite setting with automatic type routing. Args: - cfg: The configuration of the simulation. Defaults to None, - in which case the default configuration is used. + name: The setting name (e.g., "/physics/cudaDevice"). + value: The value to set (bool, int, float, str, list, or tuple). """ - # 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() - - # 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." - ) - - # 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, - ) + 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: - 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. - - 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. - """ + raise ValueError(f"Unsupported value type for setting '{name}': {type(value)}") - def has_gui(self) -> bool: - """Returns whether the simulation has a GUI enabled. + def get(self, name: str) -> Any: + """Get a Carbonite setting value.""" + return self._settings.get(name) - True if the simulation has a GUI enabled either locally or live-streamed. - """ - return self._has_gui - def has_rtx_sensors(self) -> bool: - """Returns whether the simulation has any RTX-rendering related sensors. +class SimulationContext: + """Controls simulation lifecycle including physics stepping and rendering. - 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. + This singleton class manages: - True if the simulation has RTX sensors (such as USD Cameras or LiDARs). + * Physics configuration (time-step, solver parameters via :class:`isaaclab.sim.SimulationCfg`) + * Simulation state (play, pause, step, stop) + * Rendering and visualization - For more information, please check `NVIDIA RTX documentation`_. + The singleton instance can be accessed using the ``instance()`` class method. + """ - .. _NVIDIA RTX documentation: https://developer.nvidia.com/rendering-technologies - """ - return self._settings.get_as_bool("/isaaclab/render/rtx_sensors") + # Singleton instance + _instance: "SimulationContext | None" = None - def is_fabric_enabled(self) -> bool: - """Returns whether the fabric interface is enabled. + def __new__(cls, cfg: SimulationCfg | None = None): + """Enforce singleton pattern.""" + if cls._instance is None: + cls._instance = super().__new__(cls) + cls._instance._initialized = False + return cls._instance - 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. + @classmethod + def instance(cls) -> "SimulationContext | None": + """Get the singleton instance, or None if not created.""" + return cls._instance - For more information, please check `Fabric documentation`_. + def __init__(self, cfg: SimulationCfg | None = None): + """Initialize the simulation context. - .. _Fabric documentation: https://docs.omniverse.nvidia.com/kit/docs/usdrt/latest/docs/usd_fabric_usdrt.html + Args: + cfg: Simulation configuration. Defaults to None (uses default config). """ - return self._fabric_iface is not None + # Skip initialization if already initialized + if not self._initialized: + # store input + 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() + 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] + if stage_id < 0: + stage_cache.Insert(self.stage) # type: ignore[union-attr] + + # Acquire settings interface and create helper + self.carb_settings = carb.settings.get_settings() + self._settings_helper = SettingsHelper(self.carb_settings) + + # Initialize interfaces (order matters: visualizer first for config, then physics) + self._visualizer_interface = VisualizerInterface(self) + self._physics_interface = PhysicsInterface(self) + + # List of interfaces for common operations + self._interfaces: list[Interface] = [ + self._physics_interface, + self._visualizer_interface, + ] + + # define a global variable to store the exceptions raised in the callback stack + builtins.ISAACLAB_CALLBACK_EXCEPTION = None # type: ignore[attr-defined] + + # Simulation state: playing, paused, or stopped + self._is_playing = False + self._is_stopped = True + self._initialized = True + + def _call_interfaces(self, method: str, **kwargs) -> None: + """Call a method on all interfaces.""" + for interface in self._interfaces: + getattr(interface, method)(**kwargs) + raise_callback_exception_if_any() def get_version(self) -> tuple[int, int, int]: - """Returns the version of the simulator. + """Returns the version of the simulator (major, minor, patch).""" + ver = get_isaac_sim_version() + return ver.major, ver.minor, ver.micro - The returned tuple contains the following information: + def set_setting(self, name: str, value: Any) -> None: + """Set a Carbonite setting value.""" + self._settings_helper.set(name, value) - * 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). + def get_setting(self, name: str) -> Any: + """Get a Carbonite setting value.""" + return self._settings_helper.get(name) - .. 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. + def forward(self) -> None: + """Update kinematics and sync scene data without stepping physics.""" + self._call_interfaces("forward") - Returns: - A tuple containing the major, minor, and patch versions. + def reset(self, soft: bool = False) -> None: + """Reset the simulation. - Example: - >>> sim = SimulationContext() - >>> sim.get_version() - (2022, 1, 0) + Args: + soft: If True, skip full reinitialization. """ - return get_isaac_sim_version().major, get_isaac_sim_version().minor, get_isaac_sim_version().micro + self._call_interfaces("reset", soft=soft) + self._is_playing = True + self._is_stopped = False - """ - 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. + def step(self, render: bool = True) -> None: + """Step physics, update visualizers, and optionally render. 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". + render: Whether to render the scene after stepping. Defaults to True. """ - # 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) + self._call_interfaces("step", render=render) - def set_render_mode(self, mode: RenderMode): - """Change the current render mode of the simulation. + def is_playing(self) -> bool: + """Returns True if simulation is playing (not paused or stopped).""" + return self._is_playing - Please see :class:`RenderMode` for more information on the different render modes. + def is_stopped(self) -> bool: + """Returns True if simulation is stopped (not just paused).""" + return self._is_stopped - .. 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. + def play(self) -> None: + """Start or resume the simulation.""" + self._call_interfaces("play") + self._is_playing = True + self._is_stopped = False - Args: - mode (RenderMode): The rendering mode. If different than SimulationContext's rendering mode, - SimulationContext's mode is changed to the new mode. + def pause(self) -> None: + """Pause the simulation (can be resumed with play).""" + self._call_interfaces("pause") + self._is_playing = False + # Note: _is_stopped remains False - paused is different from stopped - 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 - 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. - - .. 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 stop(self) -> None: + """Stop the simulation completely.""" + self._call_interfaces("stop") + self._is_playing = False + self._is_stopped = True - def get_setting(self, name: str) -> Any: - """Read the simulation setting using the Carbonite SDK. + def render(self, mode: int | None = None) -> None: + """Refresh rendering components (viewports, UI). Args: - name: The name of the setting. - - Returns: - The value of the setting. + mode: Render mode. Defaults to None (use current mode). """ - 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 - - """ - Operations - Override (standalone) - """ + self._physics_interface.forward() + self._visualizer_interface.render() - 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 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 get_physics_dt(self) -> float: + """Returns the physics time step.""" + return self._physics_interface.physics_dt - def step(self, render: bool = True): - """Steps the simulation. + def get_rendering_dt(self) -> float: + """Returns the rendering time step.""" + return self._visualizer_interface.get_rendering_dt() - .. note:: - This function blocks if the timeline is paused. It only returns when the timeline is playing. + @classmethod + def clear_instance(cls, clear_stage: bool = True) -> None: + """Clean up resources and clear the singleton instance. 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. + clear_stage: If True, clear stage prims (preserving /World and PhysicsScene) + before closing. 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 - - # 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. + if cls._instance is None: + return - Args: - mode: The rendering mode. Defaults to None, in which case the current rendering mode is used. - """ - # 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) + if not cls._instance._initialized: + logger.warning("Simulation context not initialized.") + return - """ - Operations - Override (extension) - """ + # Optionally clear stage contents first + if clear_stage: + cls.clear_stage() + # Close all interfaces + cls._instance._call_interfaces("close") - 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) + # 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] - """ - Initialization/Destruction - Override. - """ + # Clear instance + cls._instance._initialized = False + cls._instance = None - 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 + gc.collect() @classmethod - def clear_instance(cls): - # clear the callback - 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() - - """ - Helper Functions - """ - - 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) - - 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", - } - - 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 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.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 - ) - - # -- 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) + def clear_stage(cls) -> None: + """Clear the current USD stage (preserving /World and PhysicsScene). - # 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: + Note: + This clears stage prims but keeps the context alive. For full cleanup, + use :meth:`clear_instance` instead. + """ + if cls._instance is None: return - # 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 - - """ - Callbacks. - """ - - def _app_control_on_stop_handle_fn(self, event: carb.events.IEvent): - """Callback to deal with the app when 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" - Once the simulation is stopped, the physics handles go invalid. After that, it is not possible to - resume the simulation from the last state. This leaves the app in an inconsistent state, where - two possible actions can be taken: - - 1. **Keep the app rendering**: In this case, the simulation is kept running and the app is not shutdown. - However, the physics is not updated and the script cannot be resumed from the last state. The - user has to manually close the app to stop the simulation. - 2. **Shutdown the app**: This is the default behavior. In this case, the app is shutdown and - the simulation is stopped. - - Note: - This callback is used only when running the simulation in a standalone python script. In an extension, - it is expected that the user handles the extension shutdown. - """ - if not self._disable_app_control_on_stop_handle: - while not omni.timeline.get_timeline_interface().is_playing(): - self.render() - return + sim_utils.clear_stage(stage=cls._instance.stage, predicate=_predicate) @contextmanager @@ -1070,22 +313,15 @@ def build_simulation_context( """ 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.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: @@ -1093,13 +329,10 @@ def build_simulation_context( cfg = GroundPlaneCfg() cfg.func("/World/defaultGroundPlane", cfg) - if add_lighting or (auto_add_lighting and sim.has_gui()): + if add_lighting or (auto_add_lighting and sim.get_setting("/isaaclab/has_gui")): # Lighting 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)) @@ -1107,18 +340,9 @@ def build_simulation_context( 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/sim/spawners/materials/visual_materials.py b/source/isaaclab/isaaclab/sim/spawners/materials/visual_materials.py index 25658786467..e619de1a142 100644 --- a/source/isaaclab/isaaclab/sim/spawners/materials/visual_materials.py +++ b/source/isaaclab/isaaclab/sim/spawners/materials/visual_materials.py @@ -59,14 +59,18 @@ def spawn_preview_surface(prim_path: str, cfg: visual_materials_cfg.PreviewSurfa # since stage in memory is not supported by the "CreatePreviewSurfaceMaterialPrim" kit command attach_stage_to_usd_context(attaching_early=True) + # note: this command does not support passing 'stage' as an argument omni.kit.commands.execute("CreatePreviewSurfaceMaterialPrim", mtl_path=prim_path, select_new_prim=False) else: raise ValueError(f"A prim already exists at path: '{prim_path}'.") # obtain prim 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() + 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) @@ -108,10 +112,6 @@ def spawn_from_mdl_file(prim_path: str, cfg: visual_materials_cfg.MdlMaterialCfg # spawn material if it doesn't exist. if not stage.GetPrimAtPath(prim_path).IsValid(): - # early attach stage to usd context if stage is in memory - # since stage in memory is not supported by the "CreateMdlMaterialPrim" kit command - attach_stage_to_usd_context(attaching_early=True) - # extract material name from path material_name = cfg.mdl_path.split("/")[-1].split(".")[0] omni.kit.commands.execute( @@ -119,12 +119,16 @@ def spawn_from_mdl_file(prim_path: str, cfg: visual_materials_cfg.MdlMaterialCfg 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, ) 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() del cfg["func"] diff --git a/source/isaaclab/isaaclab/sim/utils/__init__.py b/source/isaaclab/isaaclab/sim/utils/__init__.py index 3a85ae44c2f..00c7ad5007a 100644 --- a/source/isaaclab/isaaclab/sim/utils/__init__.py +++ b/source/isaaclab/isaaclab/sim/utils/__init__.py @@ -5,9 +5,23 @@ """Utilities built around USD operations.""" +import builtins + from .legacy import * # noqa: F401, F403 from .prims import * # noqa: F401, F403 from .queries import * # noqa: F401, F403 from .semantics import * # noqa: F401, F403 from .stage import * # noqa: F401, F403 from .transforms import * # noqa: F401, F403 + + +def raise_callback_exception_if_any() -> None: + """Check for and re-raise any exception stored in the callback exception global. + + This is used to propagate exceptions from callbacks (like physics or render callbacks) + back to the main thread where they can be properly handled. + """ + 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/sim/utils/prims.py b/source/isaaclab/isaaclab/sim/utils/prims.py index a81ccd2232e..3dca1deac96 100644 --- a/source/isaaclab/isaaclab/sim/utils/prims.py +++ b/source/isaaclab/isaaclab/sim/utils/prims.py @@ -211,9 +211,15 @@ def delete_prim(prim_path: str | Sequence[str], stage: Usd.Stage | None = None) stage_cache = UsdUtils.StageCache.Get() stage_id = stage_cache.GetId(stage).ToLongInt() if stage_id < 0: + is_stage_inserted = True stage_id = stage_cache.Insert(stage).ToLongInt() + else: + is_stage_inserted = False # delete prims DeletePrimsCommand(prim_path, stage=stage).do() + # erase from cache to prevent memory leaks + if is_stage_inserted: + stage_cache.Erase(stage) def move_prim(path_from: str, path_to: str, keep_world_transform: bool = True, stage: Usd.Stage | None = None) -> None: diff --git a/source/isaaclab/isaaclab/sim/utils/stage.py b/source/isaaclab/isaaclab/sim/utils/stage.py index b4a580fffe4..6c32fa1416d 100644 --- a/source/isaaclab/isaaclab/sim/utils/stage.py +++ b/source/isaaclab/isaaclab/sim/utils/stage.py @@ -5,7 +5,8 @@ """Utilities for operating on the USD stage.""" -import builtins +from __future__ import annotations + import contextlib import logging import threading @@ -289,66 +290,67 @@ def close_stage(callback_fn: Callable[[bool, str], None] | None = None) -> bool: return result -def clear_stage(predicate: Callable[[Usd.Prim], bool] | None = None) -> None: +def clear_stage(stage: Usd.Stage | None = None, predicate: Callable[[Usd.Prim], bool] | None = None) -> None: """Deletes all prims in the stage without populating the undo command buffer. The function will delete all prims in the stage that satisfy the predicate. If the predicate - is None, a default predicate will be used that deletes all prims. The default predicate deletes - all prims that are not the root prim, are not under the /Render namespace, have the ``no_delete`` - metadata, are not ancestral to any other prim, and are not hidden in the stage window. + is None, a default predicate will be used that deletes all prims except those that meet any + of the following criteria: + + * The root prim (``"/"``) or prims under the ``/Render`` namespace + * Prims with the ``no_delete`` metadata set + * Prims with the ``hide_in_stage_window`` metadata set + * Ancestral prims (prims that are ancestors of other prims in a reference/payload chain) Args: - predicate: A user defined function that takes the USD prim as an argument and - returns a boolean indicating if the prim should be deleted. If the predicate is None, - a default predicate will be used that deletes all prims. + stage: The stage to clear. Defaults to None, in which case the current stage is used. + predicate: A user-defined function that takes a USD prim as an argument and + returns a boolean indicating if the prim should be deleted. If None, all + prims will be considered for deletion (subject to the default exclusions above). + If provided, both the default exclusions and the predicate must be satisfied + for a prim to be deleted. Example: >>> import isaaclab.sim as sim_utils >>> - >>> # clear the whole stage + >>> # Clear the whole stage (except protected prims) >>> sim_utils.clear_stage() >>> - >>> # given the stage: /World/Cube, /World/Cube_01, /World/Cube_02. + >>> # Given the stage: /World/Cube, /World/Cube_01, /World/Cube_02 >>> # Delete only the prims of type Cube >>> predicate = lambda _prim: _prim.GetTypeName() == "Cube" - >>> sim_utils.clear_stage(predicate) # after the execution the stage will be /World + >>> sim_utils.clear_stage(predicate) # After execution, the stage will only have /World """ # Note: Need to import this here to prevent circular dependencies. from .prims import delete_prim from .queries import get_all_matching_child_prims - def _default_predicate(prim: Usd.Prim) -> bool: + def _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"): + # Skip the root prim + if prim_path == "/" or prim_path == "/Render": return False - if prim.GetMetadata("hide_in_stage_window"): + # Skip prims with the "no_delete" metadata + if prim.GetMetadata("no_delete") or prim.GetMetadata("hide_in_stage_window"): return False + # Skip ancestral prims if omni.usd.check_ancestral(prim): return False - return True + # Additional predicate check + return predicate is None or predicate(prim) - def _predicate_from_path(prim: Usd.Prim) -> bool: - if predicate is None: - return _default_predicate(prim) - return predicate(prim) + # get stage handle + stage = get_current_stage() if stage is None else stage # 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, stage=stage, traverse_instance_prims=False) # convert prims to prim paths prim_paths_to_delete = [prim.GetPath().pathString for prim in prims] # delete prims - delete_prim(prim_paths_to_delete) - - if builtins.ISAAC_LAUNCHED_FROM_TERMINAL is False: # type: ignore - omni.kit.app.get_app_interface().update() + delete_prim(prim_paths_to_delete, stage) + # update stage + update_stage() def is_stage_loading() -> bool: @@ -433,7 +435,7 @@ 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.physics.physx_manager import PhysxManager from isaaclab.sim.simulation_context import SimulationContext @@ -465,14 +467,11 @@ 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) + PhysxManager.enable_stage_open_callback(False) # enable physics fabric - SimulationContext.instance()._physics_context.enable_fabric(True) # type: ignore + SimulationContext.instance().carb_settings.set_bool("/isaaclab/physics/fabric_enabled", True) # attach stage to usd context omni.usd.get_context().attach_stage_with_callback(stage_id) @@ -482,4 +481,4 @@ def attach_stage_to_usd_context(attaching_early: bool = False): physx_sim_interface.attach_stage(stage_id) # re-enable stage open callback - SimulationManager.enable_stage_open_callback(True) + PhysxManager.enable_stage_open_callback(True) diff --git a/source/isaaclab/isaaclab/ui/widgets/line_plot.py b/source/isaaclab/isaaclab/ui/widgets/line_plot.py index 90a84e201a1..e4c6706a861 100644 --- a/source/isaaclab/isaaclab/ui/widgets/line_plot.py +++ b/source/isaaclab/isaaclab/ui/widgets/line_plot.py @@ -11,7 +11,7 @@ from typing import TYPE_CHECKING import omni -from isaacsim.core.api.simulation_context import SimulationContext +from isaaclab.sim import SimulationContext with suppress(ImportError): # isaacsim.gui is not available when running in headless mode. diff --git a/source/isaaclab/isaaclab/ui/widgets/manager_live_visualizer.py b/source/isaaclab/isaaclab/ui/widgets/manager_live_visualizer.py index 685a1be5bcd..b75db289b31 100644 --- a/source/isaaclab/isaaclab/ui/widgets/manager_live_visualizer.py +++ b/source/isaaclab/isaaclab/ui/widgets/manager_live_visualizer.py @@ -12,7 +12,7 @@ from typing import TYPE_CHECKING import omni.kit.app -from isaacsim.core.api.simulation_context import SimulationContext +from isaaclab.sim import SimulationContext from isaaclab.managers import ManagerBase from isaaclab.utils import configclass diff --git a/source/isaaclab/isaaclab/visualizers/__init__.py b/source/isaaclab/isaaclab/visualizers/__init__.py new file mode 100644 index 00000000000..762874f3e19 --- /dev/null +++ b/source/isaaclab/isaaclab/visualizers/__init__.py @@ -0,0 +1,103 @@ +# # 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. + +# This sub-package contains configuration classes and implementations for different +# visualizer backends that can be used with Isaac Lab. The visualizers are used for +# debug visualization and monitoring of the simulation, separate from rendering for sensors. + +# Supported visualizers: +# - Newton OpenGL Visualizer: Lightweight OpenGL-based visualizer +# - Omniverse Visualizer: High-fidelity Omniverse-based visualizer using Isaac Sim viewport +# - Rerun Visualizer: Web-based Rerun visualizer with recording and timeline scrubbing + +# 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 TYPE_CHECKING, Any + +# # Import config classes (no circular dependency) +# from .newton_visualizer_cfg import NewtonVisualizerCfg +# from .ov_visualizer_cfg import OVVisualizerCfg +# from .rerun_visualizer_cfg import RerunVisualizerCfg + +# # Import base classes first +from .visualizer import Visualizer +from .visualizer_cfg import VisualizerCfg + +# if TYPE_CHECKING: +# from typing import Type + +# from .newton_visualizer import NewtonVisualizer +# from .ov_visualizer import OVVisualizer +# from .rerun_visualizer import RerunVisualizer + +# # Global registry for visualizer types (lazy-loaded) +# _VISUALIZER_REGISTRY: dict[str, Any] = {} + +# __all__ = [ +# "Visualizer", +# "VisualizerCfg", +# "NewtonVisualizerCfg", +# "OVVisualizerCfg", +# "RerunVisualizerCfg", +# "get_visualizer_class", +# ] + + +# # 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] + +# # Lazy-load visualizer on first access +# try: +# if name == "newton": +# from .newton_visualizer import NewtonVisualizer + +# _VISUALIZER_REGISTRY["newton"] = NewtonVisualizer +# return NewtonVisualizer +# elif name == "omniverse": +# from .ov_visualizer import OVVisualizer + +# _VISUALIZER_REGISTRY["omniverse"] = OVVisualizer +# return OVVisualizer +# elif name == "rerun": +# from .rerun_visualizer import RerunVisualizer + +# _VISUALIZER_REGISTRY["rerun"] = RerunVisualizer +# return RerunVisualizer +# else: +# return None +# except ImportError as e: +# # Log import error but don't crash - visualizer just won't be available +# import warnings + +# warnings.warn(f"Failed to load visualizer '{name}': {e}", 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..c689df4f7b7 --- /dev/null +++ b/source/isaaclab/isaaclab/visualizers/newton_visualizer.py @@ -0,0 +1,399 @@ +# 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. + + Adds two pause modes: + - Training pause: Stops physics simulation, continues rendering + - Rendering pause: Stops rendering updates, continues physics (SPACE key) + """ + + 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 training/simulation button + pause_label = "Resume Training" if self._paused_training else "Pause Training" + if imgui.button(pause_label): + self._paused_training = not self._paused_training + + # Pause rendering button + 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 # Sync with parent class pause state + + # Visualizer update frequency control + 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 # Sync with parent class pause state + return + + super().on_key_press(symbol, modifiers) + + def _render_ui(self): + if not self._fallback_draw_controls: + return super()._render_ui() + + # Render base UI first + super()._render_ui() + + # Then render a small floating window with training controls + imgui = self.ui.imgui + # Place near left panel but offset + 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 + + # Use theme colors directly + nav_highlight_color = self.ui.get_theme_color(imgui.Col_.nav_cursor, (1.0, 1.0, 1.0, 1.0)) + + # Position the window on the left side + 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)) + + # Main control panel window - use safe flag values + 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"): + # Render UI callbacks for side panel + for callback in self._ui_callbacks["side"]: + callback(self.ui.imgui) + + # Model Information section + 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) + + # Visualization Controls section + imgui.set_next_item_open(True, imgui.Cond_.appearing) + if imgui.collapsing_header("Visualization", flags=header_flags): + imgui.separator() + + # Joint visualization + show_joints = self.show_joints + changed, self.show_joints = imgui.checkbox("Show Joints", show_joints) + + # Contact visualization + show_contacts = self.show_contacts + changed, self.show_contacts = imgui.checkbox("Show Contacts", show_contacts) + + # Spring visualization + show_springs = self.show_springs + changed, self.show_springs = imgui.checkbox("Show Springs", show_springs) + + # Center of mass visualization + show_com = self.show_com + changed, self.show_com = imgui.checkbox("Show Center of Mass", show_com) + + # Rendering Options section + imgui.set_next_item_open(True, imgui.Cond_.appearing) + if imgui.collapsing_header("Rendering Options"): + imgui.separator() + + # Sky rendering + changed, self.renderer.draw_sky = imgui.checkbox("Sky", self.renderer.draw_sky) + + # Shadow rendering + changed, self.renderer.draw_shadows = imgui.checkbox("Shadows", self.renderer.draw_shadows) + + # Wireframe mode + changed, self.renderer.draw_wireframe = imgui.checkbox("Wireframe", self.renderer.draw_wireframe) + + # Light color + changed, self.renderer._light_color = imgui.color_edit3("Light Color", self.renderer._light_color) + # Sky color + changed, self.renderer.sky_upper = imgui.color_edit3("Sky Color", self.renderer.sky_upper) + # Ground color + changed, self.renderer.sky_lower = imgui.color_edit3("Ground Color", self.renderer.sky_lower) + + # Camera Information section + 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}°") + + # Camera controls hint - update to reflect new controls + 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. + + Lightweight OpenGL-based visualization with training/rendering pause controls. + """ + + 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: + """Initialize visualizer with scene data.""" + if self._is_initialized: + return + + # Import NewtonManager for metadata access + from isaaclab.physics.newton_manager import NewtonManager + + # Store scene data provider for accessing physics state + if scene_data and "scene_data_provider" in scene_data: + self._scene_data_provider = scene_data["scene_data_provider"] + + # Get Newton-specific data from scene data provider + if self._scene_data_provider: + self._model = self._scene_data_provider.get_model() + self._state = self._scene_data_provider.get_state() + else: + # Fallback: direct access to NewtonManager (for backward compatibility) + self._model = NewtonManager._model + self._state = NewtonManager._state_0 + + if self._model is None: + raise RuntimeError("Newton visualizer requires Newton Model. Ensure Newton physics is initialized first.") + + # Build metadata from NewtonManager + 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, + } + + # Create the viewer with metadata + self._viewer = NewtonViewerGL( + width=self.cfg.window_width, + height=self.cfg.window_height, + metadata=metadata, + update_frequency=self.cfg.update_frequency, + ) + + # Set the model + self._viewer.set_model(self._model) + + # Disable auto world spacing in Newton Viewer to display envs at actual world positions + self._viewer.set_world_offsets((0.0, 0.0, 0.0)) + + # Configure camera position and orientation (Z-up axis) + self._viewer.camera.pos = wp.vec3(*self.cfg.camera_position) + self._viewer.up_axis = 2 # Z-up + + # Calculate pitch and yaw from camera_position and camera_target + 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 + + # Calculate yaw and pitch for Z-up coordinate system + # Yaw: rotation around Z axis (horizontal plane) + yaw = np.degrees(np.arctan2(direction[1], direction[0])) + # Pitch: elevation angle + 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 + + # Configure visualization options + 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 + + # Configure rendering options + 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 + + # Configure colors + 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: + """Update visualizer for one step.""" + if not self._is_initialized or self._is_closed or self._viewer is None: + return + + self._sim_time += dt + self._step_counter += 1 + + # Fetch updated state from scene data provider + if self._scene_data_provider: + self._state = self._scene_data_provider.get_state() + else: + # Fallback: direct access to NewtonManager + from isaaclab.physics.newton_manager import NewtonManager + + self._state = NewtonManager._state_0 + + # Only update visualizer at the specified frequency + 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: + """Close visualizer and clean up resources.""" + if self._is_closed: + return + if self._viewer is not None: + self._viewer = None + self._is_closed = True + + def is_running(self) -> bool: + """Check if visualizer window is still open.""" + if not self._is_initialized or self._is_closed or self._viewer is None: + return False + return self._viewer.is_running() + + def is_stopped(self) -> bool: + """Check if visualizer window is closed.""" + if not self._is_initialized or self._is_closed or self._viewer is None: + return True + return False + + def supports_markers(self) -> bool: + """Newton visualizer does not have this feature yet.""" + return False + + def supports_live_plots(self) -> bool: + """Newton visualizer does not have this feature yet.""" + return False + + def is_training_paused(self) -> bool: + """Check if training is paused.""" + if not self._is_initialized or self._viewer is None: + return False + return self._viewer.is_training_paused() + + def is_rendering_paused(self) -> bool: + """Check if rendering is paused.""" + 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..922c90c010e --- /dev/null +++ b/source/isaaclab/isaaclab/visualizers/newton_visualizer_cfg.py @@ -0,0 +1,63 @@ +# 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. + + Lightweight OpenGL-based visualizer with real-time 3D rendering, interactive + camera controls, and debug visualization (contacts, joints, springs, COM). + + Requires: pyglet >= 2.1.6, imgui_bundle >= 1.92.0 + """ + + 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). Lower = more responsive but slower training.""" + + 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..234e2aee88f --- /dev/null +++ b/source/isaaclab/isaaclab/visualizers/ov_visualizer.py @@ -0,0 +1,584 @@ +# 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 asyncio +import logging +import enum +from typing import Any +import omni.kit.app +from pxr import UsdGeom + +from .ov_visualizer_cfg import OVVisualizerCfg +from .visualizer import Visualizer + +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 OVVisualizer(Visualizer): + """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 + + Lifecycle: __init__(cfg) -> initialize(scene_data) -> step() (repeated) -> close() + """ + + def __init__(self, cfg: "OVVisualizerCfg"): + """Initialize OV visualizer with configuration. + + Args: + cfg: Configuration for the visualizer. + """ + super().__init__(cfg) + self.cfg: "OVVisualizerCfg" = cfg + + # Will be set during initialize() + self._simulation_context = None + self._simulation_app = None + self._simulation_app_running = False + + # Viewport state + self._viewport_context = None + self._viewport_window = None + self._viewport_api = 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("[OVVisualizer] Already initialized.") + return + + usd_stage = None + if scene_data is not None: + usd_stage = scene_data.get("usd_stage") + self._simulation_context = scene_data.get("simulation_context") + + if usd_stage is None: + raise RuntimeError("OV visualizer requires a USD stage.") + + # Build metadata from simulation context if available + metadata = {} + if self._simulation_context is not None: + # Try to get num_envs from the simulation context's scene if available + num_envs = 0 + if hasattr(self._simulation_context, "scene") and self._simulation_context.scene is not None: + if hasattr(self._simulation_context.scene, "num_envs"): + num_envs = self._simulation_context.scene.num_envs + + # Detect physics backend (could be extended to check actual backend type) + physics_backend = "newton" # Default for now, could be made more sophisticated + + metadata = { + "num_envs": num_envs, + "physics_backend": physics_backend, + "env_prim_pattern": "/World/envs/env_{}", # Standard pattern + } + + self._simulation_context.settings.set_bool("/app/player/playSimulations", False) + self._offscreen_render = bool(self._simulation_context.settings.get("/isaaclab/render/offscreen")) + self._render_viewport = bool(self._simulation_context.settings.get("/isaaclab/render/active_viewport")) + self._has_gui = bool(self._simulation_context.settings.get("/isaaclab/render/active_viewport")) + # Set render mode + if not self._has_gui and not self._offscreen_render: + self.render_mode = RenderMode.NO_GUI_OR_RENDERING + elif not self._has_gui and self._offscreen_render: + self.render_mode = RenderMode.PARTIAL_RENDERING + else: + self.render_mode = RenderMode.FULL_RENDERING + + # enable viewport updates if GUI is enabled + if self._has_gui: + try: + import omni.ui as ui + from omni.kit.viewport.utility import get_active_viewport + self._viewport_context = get_active_viewport() + self._viewport_context.updates_enabled = True + self._viewport_window = ui.Workspace.get_window("Viewport") + except (ImportError, AttributeError): + pass + + # Disable viewport for offscreen-only rendering + if not self._render_viewport and self._offscreen_render: + try: + from omni.kit.viewport.utility import get_active_viewport + get_active_viewport().updates_enabled = False + except (ImportError, AttributeError): + pass + + 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: + """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._simulation_context is None: + return + + # check if we need to change the render mode + if mode is not None: + self.set_render_mode(mode) + + self._simulation_context.settings.set_bool("/app/player/playSimulations", False) + omni.kit.app.get_app().update() + self._simulation_context.settings.set_bool("/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._simulation_context.device: + import torch + + torch.cuda.set_device(self._simulation_context.device) + + def is_running(self) -> bool: + """Check if visualizer is still running.""" + return self.is_playing() + + 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 simulation is stopped.""" + if self._timeline is None: + return True + return self._timeline.is_stopped() + + 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() + + def is_training_paused(self) -> bool: + """Check if training is paused (always False for OV).""" + return False + + 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._simulation_context is None: + return None + + settings = self._simulation_context.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("[OVVisualizer] 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 for this viewport + camera_path = self._viewport_api.get_active_camera() + if not camera_path: + camera_path = "/OmniverseKit_Persp" # Default camera + + # Use Isaac Sim utility to set camera view + vp_utils._visualizer_interface.set_camera_view( + eye=list(eye), target=list(target), camera_prim_path=camera_path, viewport_api=self._viewport_api + ) + + logger.info(f"[OVVisualizer] Camera set: pos={eye}, target={target}, camera={camera_path}") + + 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. + + 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. + """ + # check if mode change is possible -- not possible when no GUI is available + if not getattr(self, "_has_gui", True): + 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 close(self) -> None: + """Clean up visualizer resources.""" + # Note: We don't close the SimulationApp here as it's managed by AppLauncher + self._simulation_context = None + self._simulation_app = None + self._viewport_context = None + self._viewport_window = None + self._viewport_api = None + self._is_initialized = False + self._is_closed = True + + # ------------------------------------------------------------------ + # Private methods + # ------------------------------------------------------------------ + + def _ensure_simulation_app(self) -> None: + """Ensure Isaac Sim app is running.""" + try: + # Check if omni.kit.app is available (indicates Isaac Sim is running) + import omni.kit.app + + # Get the running app instance + 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 via AppLauncher before initialization. " + "Ensure your script calls AppLauncher before creating the environment." + ) + + # Try to get SimulationApp instance for headless check + try: + from isaacsim import SimulationApp + + # Check various ways SimulationApp might store its instance + 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 + + # Check if running in headless mode + if self._simulation_app.config.get("headless", False): # pyright: ignore [reportAttributeAccessIssue] + logger.warning( + "[OVVisualizer] Running in headless mode. " + "OV visualizer requires GUI mode (launch with --headless=False) to create viewports." + ) + else: + logger.info("[OVVisualizer] Using existing Isaac Sim app instance.") + else: + # App is running but we couldn't get SimulationApp instance + # This is okay - we can still use omni APIs + logger.info("[OVVisualizer] Isaac Sim app is running (via omni.kit.app).") + self._simulation_app_running = True + except ImportError: + # SimulationApp not available, but omni.kit.app is running + logger.info("[OVVisualizer] Using running Isaac Sim app (SimulationApp module not available).") + + except ImportError as e: + raise ImportError( + f"[OVVisualizer] Could not import omni.kit.app: {e}. Isaac Sim may not be installed or not running." + ) + + def _setup_viewport(self, usd_stage, metadata: dict) -> None: + """Setup viewport with camera and window size.""" + try: + import omni.kit.viewport.utility as vp_utils + from omni.ui import DockPosition + + # Create new viewport or use existing + if self.cfg.create_viewport and self.cfg.viewport_name: + # Map dock position string to enum + 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) + + # Create new viewport with proper API + 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}'") + + # Dock the viewport asynchronously (needs to wait for window creation) + asyncio.ensure_future(self._dock_viewport_async(self.cfg.viewport_name, dock_pos)) + + # Create dedicated camera for this viewport + if self._viewport_window: + self._create_and_assign_camera(usd_stage) + else: + # Use existing viewport by name, or fall back to active viewport + 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 instead." + ) + 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 + + # Get viewport API for camera control + self._viewport_api = self._viewport_window.viewport_api + + # Set camera pose (uses existing camera if not created above) + self.set_camera_view(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 e: + logger.warning(f"[OVVisualizer] Viewport utilities unavailable: {e}") + except Exception as e: + logger.error(f"[OVVisualizer] Error setting up viewport: {e}") + + async def _dock_viewport_async(self, viewport_name: str, dock_position) -> None: + """Dock viewport window asynchronously after it's created. + + Args: + viewport_name: Name of the viewport window to dock. + dock_position: DockPosition enum value for where to dock. + """ + try: + import omni.kit.app + import omni.ui + + # Wait for the viewport window to be created in the workspace + viewport_window = None + for i in range(10): # Try up to 10 frames + 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 for docking." + ) + return + + # Get the main viewport to dock relative to + main_viewport = omni.ui.Workspace.get_window("Viewport") + if not main_viewport: + # Try alternative viewport names + 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: + # Dock the new viewport relative to the main viewport + viewport_window.dock_in(main_viewport, dock_position, 0.5) + + # Wait a frame for docking to complete + await omni.kit.app.get_app().next_update_async() + + # Make the new viewport the active/focused tab + # Try multiple methods to ensure it becomes active + viewport_window.focus() + viewport_window.visible = True + + # Wait another frame and focus again (sometimes needed for tabs) + 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 e: + logger.warning(f"[OVVisualizer] Error docking viewport: {e}") + + def _create_and_assign_camera(self, usd_stage) -> None: + """Create a dedicated camera for this viewport and assign it.""" + try: + # Create camera prim path based on viewport name + camera_path = f"/World/Cameras/{self.cfg.viewport_name}_Camera" + + # Check if camera already exists + camera_prim = usd_stage.GetPrimAtPath(camera_path) + if not camera_prim.IsValid(): + # Create camera prim + 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}") + + # Assign camera to viewport + 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 e: + logger.warning(f"[OVVisualizer] Could not create/assign camera: {e}. Using default camera.") 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..bbe0505b055 --- /dev/null +++ b/source/isaaclab/isaaclab/visualizers/ov_visualizer_cfg.py @@ -0,0 +1,49 @@ +# 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-2025, The Isaac Lab Project Developers. +# 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. + + Displays USD stage, VisualizationMarkers, and LivePlots. + Can attach to existing app or launch standalone. + """ + + visualizer_type: str = "omniverse" + """Type identifier for Omniverse visualizer.""" + + 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. + """ + + 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' (tabs with existing).""" + + window_width: int = 1280 + """Viewport width in pixels.""" + + window_height: int = 720 + """Viewport height in pixels.""" diff --git a/source/isaaclab/isaaclab/visualizers/physx_ov_visualizer.py b/source/isaaclab/isaaclab/visualizers/physx_ov_visualizer.py new file mode 100644 index 00000000000..73d6de3f81a --- /dev/null +++ b/source/isaaclab/isaaclab/visualizers/physx_ov_visualizer.py @@ -0,0 +1,765 @@ +# 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 .visualizer 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 = self._local_gui or self._livestream_gui or self._xr_gui + self._sim.carb_settings.set_bool("/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 simulation is stopped.""" + if self._timeline is None: + return True + return self._timeline.is_stopped() + + 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.""" + if self._timeline is None: + return False + return self._timeline.is_playing() + + 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.carb_settings.set_string("/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 + carb_settings = self._sim.carb_settings + + # 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 carb_settings.get("/app/runLoops/main/rateLimitEnabled"): + carb_settings.set_int("/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" + ) + carb_settings.set_bool("/app/runLoops/main/rateLimitEnabled", True) + carb_settings.set_int("/app/runLoops/main/rateLimitFrequency", rendering_hz) + self._timeline.set_target_framerate(rendering_hz) diff --git a/source/isaaclab/isaaclab/visualizers/physx_ov_visualizer_cfg.py b/source/isaaclab/isaaclab/visualizers/physx_ov_visualizer_cfg.py new file mode 100644 index 00000000000..729e782dfbd --- /dev/null +++ b/source/isaaclab/isaaclab/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 .visualizer_cfg 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/isaaclab/visualizers/rerun_visualizer.py b/source/isaaclab/isaaclab/visualizers/rerun_visualizer.py new file mode 100644 index 00000000000..fcad36a7ccd --- /dev/null +++ b/source/isaaclab/isaaclab/visualizers/rerun_visualizer.py @@ -0,0 +1,291 @@ +# 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 + +# Set up logger +logger = logging.getLogger(__name__) + +# Try to import rerun and Newton's ViewerRerun +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, + ): + """Initialize Newton ViewerRerun wrapper.""" + # Call parent with Newton parameters + super().__init__( + app_id=app_id, + web_port=web_port, + serve_web_viewer=True, # always launch local web viewer in browser + keep_historical_data=keep_historical_data, + keep_scalar_history=keep_scalar_history, + record_to_rrd=record_to_rrd, + ) + + # Isaac Lab state + self._metadata = metadata or {} + + # Log metadata on initialization + self._log_metadata() + + def _log_metadata(self) -> None: + """Log scene metadata to Rerun as text.""" + metadata_text = "# Isaac Lab Scene Metadata\n\n" + + # Physics info + physics_backend = self._metadata.get("physics_backend", "unknown") + metadata_text += f"**Physics Backend:** {physics_backend}\n" + + # Environment info + num_envs = self._metadata.get("num_envs", 0) + metadata_text += f"**Total Environments:** {num_envs}\n" + + # Additional metadata + for key, value in self._metadata.items(): + if key not in ["physics_backend", "num_envs"]: + metadata_text += f"**{key}:** {value}\n" + + # Log to Rerun + 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. + + Requires Newton physics backend and rerun-sdk (pip install rerun-sdk).""" + + def __init__(self, cfg: RerunVisualizerCfg): + """Initialize Rerun visualizer.""" + 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: + """Initialize visualizer with Newton Model and State.""" + if self._is_initialized: + logger.warning("[RerunVisualizer] Already initialized. Skipping re-initialization.") + return + + # Import NewtonManager for metadata access + from isaaclab.physics.newton_manager import NewtonManager + + # Store scene data provider for accessing physics state + if scene_data and "scene_data_provider" in scene_data: + self._scene_data_provider = scene_data["scene_data_provider"] + + # Get Newton-specific data from scene data provider + if self._scene_data_provider: + self._model = self._scene_data_provider.get_model() + self._state = self._scene_data_provider.get_state() + else: + # Fallback: direct access to NewtonManager (for backward compatibility) + self._model = NewtonManager._model + self._state = NewtonManager._state_0 + + # Validate required Newton data + if self._model is None: + raise RuntimeError( + "Rerun visualizer requires a Newton Model. " + "Make sure Newton physics is initialized before creating the visualizer." + ) + + if self._state is None: + logger.warning("[RerunVisualizer] No Newton State available. Visualization may not work correctly.") + + # Build metadata from NewtonManager + 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, + } + + # Create Newton ViewerRerun wrapper + 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, + ) + + # Set the model + self._viewer.set_model(self._model) + + # Disable auto world spacing in Newton Viewer to display envs at actual world positions + self._viewer.set_world_offsets((0.0, 0.0, 0.0)) + + # Set initial camera view using Rerun's blueprint system + try: + # Get camera configuration + cam_pos = self.cfg.camera_position + cam_target = self.cfg.camera_target + + # Create blueprint with 3D view and camera settings + 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 e: + logger.warning(f"[RerunVisualizer] Could not set initial camera view: {e}") + + # Log initialization + num_envs = metadata.get("num_envs", 0) + physics_backend = metadata.get("physics_backend", "newton") + logger.info(f"[RerunVisualizer] Initialized with {num_envs} environments (physics: {physics_backend})") + + self._is_initialized = True + + except Exception as e: + logger.error(f"[RerunVisualizer] Failed to initialize viewer: {e}") + raise + + def step(self, dt: float, state: Any | None = None) -> None: + """Update visualizer each step. + + This method: + 1. Fetches updated state from NewtonManager + 2. Logs current state to Rerun (transforms, meshes) + 3. Actively logs markers (if enabled) + 4. Actively logs plot data (if enabled) + + Args: + dt: Time step in seconds. + state: Unused (deprecated parameter, kept for API compatibility). + """ + if not self._is_initialized or self._viewer is None: + logger.warning("[RerunVisualizer] Not initialized. Call initialize() first.") + return + + # Fetch updated state from scene data provider + if self._scene_data_provider: + self._state = self._scene_data_provider.get_state() + else: + # Fallback: direct access to NewtonManager + from isaaclab.physics.newton_manager import NewtonManager + + self._state = NewtonManager._state_0 + + # Update internal time + self._sim_time += dt + + # Begin frame with current simulation time + self._viewer.begin_frame(self._sim_time) + + # Log state (transforms) - Newton's ViewerRerun handles this + if self._state is not None: + self._viewer.log_state(self._state) + + # End frame + self._viewer.end_frame() + + def close(self) -> None: + """Clean up Rerun visualizer resources and finalize recordings.""" + 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 e: + logger.warning(f"[RerunVisualizer] Error during close: {e}") + + self._viewer = None + self._is_initialized = False + + def is_running(self) -> bool: + """Check if visualizer is running. + + Returns: + True if viewer is initialized and running, False otherwise. + """ + if self._viewer is None: + return False + return self._viewer.is_running() + + def is_stopped(self) -> bool: + """Check if visualizer is stopped.""" + if self._viewer is None: + return True + return False + + def is_training_paused(self) -> bool: + """Check if training is paused. + + Note: + Rerun visualizer currently uses Rerun's built-in timeline controls for playback. + """ + return False + + def supports_markers(self) -> bool: + """Rerun visualizer does not have this feature yet.""" + return False + + def supports_live_plots(self) -> bool: + """Rerun visualizer does not have this feature yet.""" + 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..3dc4909e4db --- /dev/null +++ b/source/isaaclab/isaaclab/visualizers/rerun_visualizer_cfg.py @@ -0,0 +1,39 @@ +# 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). + + Provides time scrubbing, 3D navigation, data filtering, and .rrd recording. + Requires Newton physics backend and rerun-sdk: `pip install rerun-sdk` + """ + + 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 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/assets/check_external_force.py b/source/isaaclab/test/assets/check_external_force.py index f666135ba3b..0c6e2ec02a4 100644 --- a/source/isaaclab/test/assets/check_external_force.py +++ b/source/isaaclab/test/assets/check_external_force.py @@ -54,7 +54,7 @@ def main(): # Load kit helper sim = SimulationContext(sim_utils.SimulationCfg(dt=0.005)) # Set main camera - sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) + sim._visualizer_interface.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) # Spawn things into stage # Ground-plane diff --git a/source/isaaclab/test/assets/check_fixed_base_assets.py b/source/isaaclab/test/assets/check_fixed_base_assets.py index c62c5a3334d..c4e5994524b 100644 --- a/source/isaaclab/test/assets/check_fixed_base_assets.py +++ b/source/isaaclab/test/assets/check_fixed_base_assets.py @@ -145,7 +145,7 @@ def main(): # Initialize the simulation context sim = sim_utils.SimulationContext(sim_utils.SimulationCfg(dt=0.01)) # Set main camera - sim.set_camera_view(eye=[2.5, 2.5, 2.5], target=[0.0, 0.0, 0.0]) + sim._visualizer_interface.set_camera_view(eye=[2.5, 2.5, 2.5], target=[0.0, 0.0, 0.0]) # design scene scene_entities, scene_origins = design_scene() scene_origins = torch.tensor(scene_origins, device=sim.device) diff --git a/source/isaaclab/test/assets/check_ridgeback_franka.py b/source/isaaclab/test/assets/check_ridgeback_franka.py index 724cd8b2a08..53bc559d60f 100644 --- a/source/isaaclab/test/assets/check_ridgeback_franka.py +++ b/source/isaaclab/test/assets/check_ridgeback_franka.py @@ -149,7 +149,7 @@ def main(): # Initialize the simulation context sim = sim_utils.SimulationContext(sim_utils.SimulationCfg()) # Set main camera - sim.set_camera_view([1.5, 1.5, 1.5], [0.0, 0.0, 0.0]) + sim._visualizer_interface.set_camera_view([1.5, 1.5, 1.5], [0.0, 0.0, 0.0]) # design scene robot = design_scene() # Play the simulator diff --git a/source/isaaclab/test/assets/test_articulation.py b/source/isaaclab/test/assets/test_articulation.py index ab6c9534fa9..57fdb9744e2 100644 --- a/source/isaaclab/test/assets/test_articulation.py +++ b/source/isaaclab/test/assets/test_articulation.py @@ -252,7 +252,7 @@ def test_initialization_floating_base_non_root(sim, num_articulations, device, a # perform rendering sim.step() # update articulation - articulation.update(sim.cfg.dt) + articulation.update(sim.cfg.physics_manager_cfg.dt) @pytest.mark.parametrize("num_articulations", [1, 2]) @@ -310,7 +310,7 @@ def test_initialization_floating_base(sim, num_articulations, device, add_ground # perform rendering sim.step() # update articulation - articulation.update(sim.cfg.dt) + articulation.update(sim.cfg.physics_manager_cfg.dt) @pytest.mark.parametrize("num_articulations", [1, 2]) @@ -367,7 +367,7 @@ def test_initialization_fixed_base(sim, num_articulations, device): # perform rendering sim.step() # update articulation - articulation.update(sim.cfg.dt) + articulation.update(sim.cfg.physics_manager_cfg.dt) # check that the root is at the correct state - its default state as it is fixed base default_root_state = articulation.data.default_root_state.clone() @@ -431,7 +431,7 @@ def test_initialization_fixed_base_single_joint(sim, num_articulations, device, # perform rendering sim.step() # update articulation - articulation.update(sim.cfg.dt) + articulation.update(sim.cfg.physics_manager_cfg.dt) # check that the root is at the correct state - its default state as it is fixed base default_root_state = articulation.data.default_root_state.clone() @@ -491,7 +491,7 @@ def test_initialization_hand_with_tendons(sim, num_articulations, device): # perform rendering sim.step() # update articulation - articulation.update(sim.cfg.dt) + articulation.update(sim.cfg.physics_manager_cfg.dt) @pytest.mark.parametrize("num_articulations", [1, 2]) @@ -544,7 +544,7 @@ def test_initialization_floating_base_made_fixed_base(sim, num_articulations, de # perform rendering sim.step() # update articulation - articulation.update(sim.cfg.dt) + articulation.update(sim.cfg.physics_manager_cfg.dt) # check that the root is at the correct state - its default state as it is fixed base default_root_state = articulation.data.default_root_state.clone() @@ -603,7 +603,7 @@ def test_initialization_fixed_base_made_floating_base(sim, num_articulations, de # perform rendering sim.step() # update articulation - articulation.update(sim.cfg.dt) + articulation.update(sim.cfg.physics_manager_cfg.dt) @pytest.mark.parametrize("num_articulations", [1, 2]) @@ -861,7 +861,7 @@ def test_external_force_buffer(sim, num_articulations, device): sim.step() # update buffers - articulation.update(sim.cfg.dt) + articulation.update(sim.cfg.physics_manager_cfg.dt) @pytest.mark.parametrize("num_articulations", [1, 2]) @@ -917,7 +917,7 @@ def test_external_force_on_single_body(sim, num_articulations, device): # perform step sim.step() # update buffers - articulation.update(sim.cfg.dt) + articulation.update(sim.cfg.physics_manager_cfg.dt) # check condition that the articulations have fallen down for i in range(num_articulations): assert articulation.data.root_pos_w[i, 2].item() < 0.2 @@ -984,7 +984,7 @@ def test_external_force_on_single_body_at_position(sim, num_articulations, devic # perform step sim.step() # update buffers - articulation.update(sim.cfg.dt) + articulation.update(sim.cfg.physics_manager_cfg.dt) # check condition that the articulations have fallen down for i in range(num_articulations): assert articulation.data.root_pos_w[i, 2].item() < 0.2 @@ -1042,7 +1042,7 @@ def test_external_force_on_multiple_bodies(sim, num_articulations, device): # perform step sim.step() # update buffers - articulation.update(sim.cfg.dt) + articulation.update(sim.cfg.physics_manager_cfg.dt) # check condition for i in range(num_articulations): # since there is a moment applied on the articulation, the articulation should rotate @@ -1108,7 +1108,7 @@ def test_external_force_on_multiple_bodies_at_position(sim, num_articulations, d # perform step sim.step() # update buffers - articulation.update(sim.cfg.dt) + articulation.update(sim.cfg.physics_manager_cfg.dt) # check condition for i in range(num_articulations): # since there is a moment applied on the articulation, the articulation should rotate @@ -1523,7 +1523,7 @@ def test_apply_joint_command(sim, num_articulations, device, add_ground_plane): # perform step sim.step() # update buffers - articulation.update(sim.cfg.dt) + articulation.update(sim.cfg.physics_manager_cfg.dt) # reset dof state joint_pos = articulation.data.default_joint_pos @@ -1537,7 +1537,7 @@ def test_apply_joint_command(sim, num_articulations, device, add_ground_plane): # perform step sim.step() # update buffers - articulation.update(sim.cfg.dt) + articulation.update(sim.cfg.physics_manager_cfg.dt) # Check that current joint position is not the same as default joint position, meaning # the articulation moved. We can't check that it reached its desired joint position as the gains @@ -1597,7 +1597,7 @@ def test_body_root_state(sim, num_articulations, device, with_offset): # perform step sim.step() # update buffers - articulation.update(sim.cfg.dt) + articulation.update(sim.cfg.physics_manager_cfg.dt) # get state properties root_state_w = articulation.data.root_state_w @@ -1717,7 +1717,7 @@ def test_write_root_state(sim, num_articulations, device, with_offset, state_loc # perform step sim.step() # update buffers - articulation.update(sim.cfg.dt) + articulation.update(sim.cfg.physics_manager_cfg.dt) if state_location == "com": if i % 2 == 0: @@ -1778,7 +1778,7 @@ def test_body_incoming_joint_wrench_b_single_joint(sim, num_articulations, devic # perform step sim.step() # update buffers - articulation.update(sim.cfg.dt) + articulation.update(sim.cfg.physics_manager_cfg.dt) # check shape assert articulation.data.body_incoming_joint_wrench_b.shape == (num_articulations, articulation.num_bodies, 6) @@ -1789,7 +1789,7 @@ def test_body_incoming_joint_wrench_b_single_joint(sim, num_articulations, devic quat_w = articulation.data.body_quat_w mass_link2 = mass[:, 1].view(num_articulations, -1) - gravity = torch.tensor(sim.cfg.gravity, device="cpu").repeat(num_articulations, 1).view((num_articulations, 3)) + gravity = torch.tensor(sim.cfg.physics_manager_cfg.gravity, device="cpu").repeat(num_articulations, 1).view((num_articulations, 3)) # NOTE: the com and link pose for single joint are colocated weight_vector_w = mass_link2 * gravity @@ -1988,7 +1988,7 @@ def test_spatial_tendons(sim, num_articulations, device): # perform rendering sim.step() # update articulation - articulation.update(sim.cfg.dt) + articulation.update(sim.cfg.physics_manager_cfg.dt) @pytest.mark.parametrize("add_ground_plane", [True]) @@ -2008,7 +2008,7 @@ def test_write_joint_frictions_to_sim(sim, num_articulations, device, add_ground # perform step sim.step() # update buffers - articulation.update(sim.cfg.dt) + articulation.update(sim.cfg.physics_manager_cfg.dt) # apply action to the articulation dynamic_friction = torch.rand(num_articulations, articulation.num_joints, device=device) @@ -2030,7 +2030,7 @@ def test_write_joint_frictions_to_sim(sim, num_articulations, device, add_ground # perform step sim.step() # update buffers - articulation.update(sim.cfg.dt) + articulation.update(sim.cfg.physics_manager_cfg.dt) if get_isaac_sim_version().major >= 5: friction_props_from_sim = articulation.root_physx_view.get_dof_friction_properties() @@ -2053,7 +2053,7 @@ def test_write_joint_frictions_to_sim(sim, num_articulations, device, add_ground # Warm up a few steps to populate buffers for _ in range(100): sim.step() - articulation.update(sim.cfg.dt) + articulation.update(sim.cfg.physics_manager_cfg.dt) # New random coefficients dynamic_friction_2 = torch.rand(num_articulations, articulation.num_joints, device=device) @@ -2074,7 +2074,7 @@ def test_write_joint_frictions_to_sim(sim, num_articulations, device, add_ground # Step to let sim ingest new params and refresh data buffers for _ in range(100): sim.step() - articulation.update(sim.cfg.dt) + articulation.update(sim.cfg.physics_manager_cfg.dt) friction_props_from_sim_2 = articulation.root_physx_view.get_dof_friction_properties() joint_friction_coeff_sim_2 = friction_props_from_sim_2[:, :, 0] diff --git a/source/isaaclab/test/assets/test_deformable_object.py b/source/isaaclab/test/assets/test_deformable_object.py index 90c183e38f6..34e8158fe30 100644 --- a/source/isaaclab/test/assets/test_deformable_object.py +++ b/source/isaaclab/test/assets/test_deformable_object.py @@ -133,7 +133,7 @@ def test_initialization(sim, num_cubes, material_path): # Simulate physics for _ in range(2): sim.step() - cube_object.update(sim.cfg.dt) + cube_object.update(sim.cfg.physics_manager_cfg.dt) # Check sim data assert cube_object.data.sim_element_quat_w.shape == (num_cubes, cube_object.max_sim_elements_per_body, 4) @@ -200,7 +200,7 @@ def test_initialization_with_kinematic_enabled(sim, num_cubes): # Simulate physics for _ in range(2): sim.step() - cube_object.update(sim.cfg.dt) + cube_object.update(sim.cfg.physics_manager_cfg.dt) default_nodal_state_w = cube_object.data.default_nodal_state_w.clone() torch.testing.assert_close(cube_object.data.nodal_state_w, default_nodal_state_w) @@ -254,7 +254,7 @@ def test_set_nodal_state(sim, num_cubes): torch.testing.assert_close(cube_object.data.nodal_state_w, nodal_state, rtol=1e-5, atol=1e-5) sim.step() - cube_object.update(sim.cfg.dt) + cube_object.update(sim.cfg.physics_manager_cfg.dt) @pytest.mark.parametrize("num_cubes", [1, 2]) @@ -300,7 +300,7 @@ def test_set_nodal_state_with_applied_transform(sim, num_cubes, randomize_pos, r for _ in range(50): sim.step() - cube_object.update(sim.cfg.dt) + cube_object.update(sim.cfg.physics_manager_cfg.dt) torch.testing.assert_close(cube_object.data.root_pos_w, mean_nodal_pos_init, rtol=1e-5, atol=1e-5) @@ -331,7 +331,7 @@ def test_set_kinematic_targets(sim, num_cubes): for _ in range(20): sim.step() - cube_object.update(sim.cfg.dt) + cube_object.update(sim.cfg.physics_manager_cfg.dt) torch.testing.assert_close( cube_object.data.nodal_pos_w[0], nodal_kinematic_targets[0, :, :3], rtol=1e-5, atol=1e-5 diff --git a/source/isaaclab/test/assets/test_rigid_object.py b/source/isaaclab/test/assets/test_rigid_object.py index 3a4d34847e5..2d7c1e5d79e 100644 --- a/source/isaaclab/test/assets/test_rigid_object.py +++ b/source/isaaclab/test/assets/test_rigid_object.py @@ -125,7 +125,7 @@ def test_initialization(num_cubes, device): # perform rendering sim.step() # update object - cube_object.update(sim.cfg.dt) + cube_object.update(sim.cfg.physics_manager_cfg.dt) @pytest.mark.parametrize("num_cubes", [1, 2]) @@ -157,7 +157,7 @@ def test_initialization_with_kinematic_enabled(num_cubes, device): # perform rendering sim.step() # update object - cube_object.update(sim.cfg.dt) + cube_object.update(sim.cfg.physics_manager_cfg.dt) # check that the object is kinematic default_root_state = cube_object.data.default_root_state.clone() default_root_state[:, :3] += origins @@ -276,7 +276,7 @@ def test_external_force_buffer(device): sim.step() # update buffers - cube_object.update(sim.cfg.dt) + cube_object.update(sim.cfg.physics_manager_cfg.dt) @pytest.mark.parametrize("num_cubes", [2, 4]) @@ -331,7 +331,7 @@ def test_external_force_on_single_body(num_cubes, device): sim.step() # update buffers - cube_object.update(sim.cfg.dt) + cube_object.update(sim.cfg.physics_manager_cfg.dt) # First object should still be at the same Z position (1.0) torch.testing.assert_close( @@ -397,7 +397,7 @@ def test_external_force_on_single_body_at_position(num_cubes, device): sim.step() # update buffers - cube_object.update(sim.cfg.dt) + cube_object.update(sim.cfg.physics_manager_cfg.dt) # The first object should be rotating around it's X axis assert torch.all(torch.abs(cube_object.data.root_ang_vel_b[0::2, 0]) > 0.1) @@ -469,7 +469,7 @@ def test_set_rigid_object_state(num_cubes, device): value = getattr(cube_object.data, key) torch.testing.assert_close(value, expected_value, rtol=1e-5, atol=1e-5) - cube_object.update(sim.cfg.dt) + cube_object.update(sim.cfg.physics_manager_cfg.dt) @pytest.mark.parametrize("num_cubes", [1, 2]) @@ -490,7 +490,7 @@ def test_reset_rigid_object(num_cubes, device): sim.step() # update object - cube_object.update(sim.cfg.dt) + cube_object.update(sim.cfg.physics_manager_cfg.dt) # Move the object to a random position root_state = cube_object.data.default_root_state.clone() @@ -541,7 +541,7 @@ def test_rigid_body_set_material_properties(num_cubes, device): # perform rendering sim.step() # update object - cube_object.update(sim.cfg.dt) + cube_object.update(sim.cfg.physics_manager_cfg.dt) # Get material properties materials_to_check = cube_object.root_physx_view.get_material_properties() @@ -595,7 +595,7 @@ def test_rigid_body_no_friction(num_cubes, device): # perform rendering sim.step() # update object - cube_object.update(sim.cfg.dt) + cube_object.update(sim.cfg.physics_manager_cfg.dt) # Non-deterministic when on GPU, so we use different tolerances if device == "cuda:0": @@ -652,10 +652,10 @@ def test_rigid_body_with_static_friction(num_cubes, device): # let everything settle for _ in range(100): sim.step() - cube_object.update(sim.cfg.dt) + cube_object.update(sim.cfg.physics_manager_cfg.dt) cube_object.write_root_velocity_to_sim(torch.zeros((num_cubes, 6), device=sim.device)) cube_mass = cube_object.root_physx_view.get_masses() - gravity_magnitude = abs(sim.cfg.gravity[2]) + gravity_magnitude = abs(sim.cfg.physics_manager_cfg.gravity[2]) # 2 cases: force applied is below and above mu # below mu: block should not move as the force applied is <= mu # above mu: block should move as the force applied is > mu @@ -682,7 +682,7 @@ def test_rigid_body_with_static_friction(num_cubes, device): cube_object.write_data_to_sim() sim.step() # update object - cube_object.update(sim.cfg.dt) + cube_object.update(sim.cfg.physics_manager_cfg.dt) if force == "below_mu": # Assert that the block has not moved torch.testing.assert_close(cube_object.data.root_pos_w, initial_root_pos, rtol=2e-3, atol=2e-3) @@ -750,7 +750,7 @@ def test_rigid_body_with_restitution(num_cubes, device): sim.step() # update object - cube_object.update(sim.cfg.dt) + cube_object.update(sim.cfg.physics_manager_cfg.dt) curr_z_velocity = cube_object.data.root_lin_vel_w[:, 2].clone() if expected_collision_type == "inelastic": @@ -804,7 +804,7 @@ def test_rigid_body_set_mass(num_cubes, device): # perform rendering sim.step() # update object - cube_object.update(sim.cfg.dt) + cube_object.update(sim.cfg.physics_manager_cfg.dt) masses_to_check = cube_object.root_physx_view.get_masses() @@ -842,7 +842,7 @@ def test_gravity_vec_w(num_cubes, device, gravity_enabled): # perform rendering sim.step() # update object - cube_object.update(sim.cfg.dt) + cube_object.update(sim.cfg.physics_manager_cfg.dt) # Expected gravity value is the acceleration of the body gravity = torch.zeros(num_cubes, 1, 6, device=device) @@ -895,7 +895,7 @@ def test_body_root_state_properties(num_cubes, device, with_offset): # perform rendering sim.step() # update object - cube_object.update(sim.cfg.dt) + cube_object.update(sim.cfg.physics_manager_cfg.dt) # get state properties root_state_w = cube_object.data.root_state_w @@ -1001,7 +1001,7 @@ def test_write_root_state(num_cubes, device, with_offset, state_location): # perform step sim.step() # update buffers - cube_object.update(sim.cfg.dt) + cube_object.update(sim.cfg.physics_manager_cfg.dt) if state_location == "com": if i % 2 == 0: @@ -1063,7 +1063,7 @@ def test_write_state_functions_data_consistency(num_cubes, device, with_offset, # perform step sim.step() # update buffers - cube_object.update(sim.cfg.dt) + cube_object.update(sim.cfg.physics_manager_cfg.dt) if state_location == "com": cube_object.write_root_com_state_to_sim(rand_state) diff --git a/source/isaaclab/test/assets/test_rigid_object_collection.py b/source/isaaclab/test/assets/test_rigid_object_collection.py index 3e75bf6c14a..581c4f66ad5 100644 --- a/source/isaaclab/test/assets/test_rigid_object_collection.py +++ b/source/isaaclab/test/assets/test_rigid_object_collection.py @@ -131,7 +131,7 @@ def test_initialization(sim, num_envs, num_cubes, device): # Simulate physics for _ in range(2): sim.step() - object_collection.update(sim.cfg.dt) + object_collection.update(sim.cfg.physics_manager_cfg.dt) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @@ -193,7 +193,7 @@ def test_initialization_with_kinematic_enabled(sim, num_envs, num_cubes, device) # Simulate physics for _ in range(2): sim.step() - object_collection.update(sim.cfg.dt) + object_collection.update(sim.cfg.physics_manager_cfg.dt) # check that the object is kinematic default_object_state = object_collection.data.default_object_state.clone() default_object_state[..., :3] += origins.unsqueeze(1) @@ -268,7 +268,7 @@ def test_external_force_buffer(sim, device): # apply action to the object collection object_collection.write_data_to_sim() sim.step() - object_collection.update(sim.cfg.dt) + object_collection.update(sim.cfg.physics_manager_cfg.dt) @pytest.mark.parametrize("num_envs", [1, 2]) @@ -307,7 +307,7 @@ def test_external_force_on_single_body(sim, num_envs, num_cubes, device): # step sim sim.step() # update object collection - object_collection.update(sim.cfg.dt) + object_collection.update(sim.cfg.physics_manager_cfg.dt) # First object should still be at the same Z position (1.0) torch.testing.assert_close( @@ -364,7 +364,7 @@ def test_external_force_on_single_body_at_position(sim, num_envs, num_cubes, dev # step sim sim.step() # update object collection - object_collection.update(sim.cfg.dt) + object_collection.update(sim.cfg.physics_manager_cfg.dt) # First object should be rotating around it's X axis assert torch.all(object_collection.data.object_ang_vel_b[:, 0::2, 0] > 0.1) @@ -434,7 +434,7 @@ def test_set_object_state(sim, num_envs, num_cubes, device, gravity_enabled): value = getattr(object_collection.data, key) torch.testing.assert_close(value, expected_value, rtol=1e-5, atol=1e-5) - object_collection.update(sim.cfg.dt) + object_collection.update(sim.cfg.physics_manager_cfg.dt) @pytest.mark.parametrize("num_envs", [1, 4]) @@ -477,7 +477,7 @@ def test_object_state_properties(sim, num_envs, num_cubes, device, with_offset, # spin the object around Z axis (com) cube_object.write_object_velocity_to_sim(spin_twist.repeat(num_envs, num_cubes, 1)) sim.step() - cube_object.update(sim.cfg.dt) + cube_object.update(sim.cfg.physics_manager_cfg.dt) # get state properties object_state_w = cube_object.data.object_state_w @@ -570,7 +570,7 @@ def test_write_object_state(sim, num_envs, num_cubes, device, with_offset, state object_ids = object_ids.to(device) for i in range(10): sim.step() - cube_object.update(sim.cfg.dt) + cube_object.update(sim.cfg.physics_manager_cfg.dt) if state_location == "com": if i % 2 == 0: @@ -599,7 +599,7 @@ def test_reset_object_collection(sim, num_envs, num_cubes, device): for i in range(5): sim.step() - object_collection.update(sim.cfg.dt) + object_collection.update(sim.cfg.physics_manager_cfg.dt) # Move the object to a random position object_state = object_collection.data.default_object_state.clone() @@ -640,7 +640,7 @@ def test_set_material_properties(sim, num_envs, num_cubes, device): # Perform simulation sim.step() - object_collection.update(sim.cfg.dt) + object_collection.update(sim.cfg.physics_manager_cfg.dt) # Get material properties materials_to_check = object_collection.root_physx_view.get_material_properties() @@ -670,7 +670,7 @@ def test_gravity_vec_w(sim, num_envs, num_cubes, device, gravity_enabled): # Perform simulation for _ in range(2): sim.step() - object_collection.update(sim.cfg.dt) + object_collection.update(sim.cfg.physics_manager_cfg.dt) # Expected gravity value is the acceleration of the body gravity = torch.zeros(num_envs, num_cubes, 6, device=device) @@ -724,7 +724,7 @@ def test_write_object_state_functions_data_consistency( env_ids = env_ids.to(device) object_ids = object_ids.to(device) sim.step() - cube_object.update(sim.cfg.dt) + cube_object.update(sim.cfg.physics_manager_cfg.dt) object_link_to_com_pos, object_link_to_com_quat = subtract_frame_transforms( cube_object.data.object_link_state_w[..., :3].view(-1, 3), diff --git a/source/isaaclab/test/assets/test_surface_gripper.py b/source/isaaclab/test/assets/test_surface_gripper.py index 86f112fdf98..c13f2fcd513 100644 --- a/source/isaaclab/test/assets/test_surface_gripper.py +++ b/source/isaaclab/test/assets/test_surface_gripper.py @@ -196,8 +196,8 @@ def test_initialization(sim, num_articulations, device, add_ground_plane) -> Non # perform rendering sim.step() # update articulation - articulation.update(sim.cfg.dt) - surface_gripper.update(sim.cfg.dt) + articulation.update(sim.cfg.physics_manager_cfg.dt) + surface_gripper.update(sim.cfg.physics_manager_cfg.dt) @pytest.mark.parametrize("device", ["cuda:0"]) diff --git a/source/isaaclab/test/controllers/test_differential_ik.py b/source/isaaclab/test/controllers/test_differential_ik.py index 65ce828129f..6774c1b97fa 100644 --- a/source/isaaclab/test/controllers/test_differential_ik.py +++ b/source/isaaclab/test/controllers/test_differential_ik.py @@ -77,8 +77,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 2533eaeeb59..b2e16c3c961 100644 --- a/source/isaaclab/test/controllers/test_operational_space.py +++ b/source/isaaclab/test/controllers/test_operational_space.py @@ -202,8 +202,6 @@ def sim(): # Cleanup sim.stop() - sim.clear() - sim.clear_all_callbacks() sim.clear_instance() diff --git a/source/isaaclab/test/controllers/test_pink_ik.py b/source/isaaclab/test/controllers/test_pink_ik.py index e16e0a0f549..ff10b34ee37 100644 --- a/source/isaaclab/test/controllers/test_pink_ik.py +++ b/source/isaaclab/test/controllers/test_pink_ik.py @@ -118,7 +118,7 @@ def env_and_cfg(request): right_eef_urdf_link_name = right_candidates[0] # Set up camera view - env.sim.set_camera_view(eye=[2.5, 2.5, 2.5], target=[0.0, 0.0, 1.0]) + env.sim._visualizer_interface.set_camera_view(eye=[2.5, 2.5, 2.5], target=[0.0, 0.0, 1.0]) # Create test parameters from test_cfg test_params = { diff --git a/source/isaaclab/test/deps/isaacsim/check_ref_count.py b/source/isaaclab/test/deps/isaacsim/check_ref_count.py index 2df1bff66ec..ff471d84402 100644 --- a/source/isaaclab/test/deps/isaacsim/check_ref_count.py +++ b/source/isaaclab/test/deps/isaacsim/check_ref_count.py @@ -40,7 +40,7 @@ import isaacsim.core.utils.nucleus as nucleus_utils import isaacsim.core.utils.prims as prim_utils -from isaacsim.core.api.simulation_context import SimulationContext +from isaaclab.sim import SimulationContext from isaacsim.core.prims import Articulation # import logger @@ -142,7 +142,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/deps/isaacsim/check_rep_texture_randomizer.py b/source/isaaclab/test/deps/isaacsim/check_rep_texture_randomizer.py index e6d43b00f9f..6dee007a51b 100644 --- a/source/isaaclab/test/deps/isaacsim/check_rep_texture_randomizer.py +++ b/source/isaaclab/test/deps/isaacsim/check_rep_texture_randomizer.py @@ -46,7 +46,7 @@ import torch import omni.replicator.core as rep -from isaacsim.core.api.simulation_context import SimulationContext +from isaaclab.sim import SimulationContext from isaacsim.core.cloner import GridCloner from isaacsim.core.objects import DynamicSphere from isaacsim.core.prims import RigidPrim @@ -91,7 +91,7 @@ def main(): env_positions = cloner.clone( source_prim_path="/World/envs/env_0", prim_paths=envs_prim_paths, replicate_physics=True, copy_from_source=True ) - physics_scene_path = sim.get_physics_context().prim_path + 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"] ) diff --git a/source/isaaclab/test/devices/check_keyboard.py b/source/isaaclab/test/devices/check_keyboard.py index 4b821bfb113..82259538709 100644 --- a/source/isaaclab/test/devices/check_keyboard.py +++ b/source/isaaclab/test/devices/check_keyboard.py @@ -23,7 +23,7 @@ import ctypes -from isaacsim.core.api.simulation_context import SimulationContext +from isaaclab.sim import SimulationContext from isaaclab.devices import Se3Keyboard, Se3KeyboardCfg diff --git a/source/isaaclab/test/devices/test_oxr_device.py b/source/isaaclab/test/devices/test_oxr_device.py index 6a9bdd8b0f6..f022016d8ba 100644 --- a/source/isaaclab/test/devices/test_oxr_device.py +++ b/source/isaaclab/test/devices/test_oxr_device.py @@ -78,7 +78,7 @@ def __post_init__(self): """Post initialization.""" self.decimation = 5 self.episode_length_s = 30.0 - self.sim.dt = 0.01 # 100Hz + self.sim.physics_manager_cfg.dt = 0.01 # 100Hz self.sim.render_interval = 2 diff --git a/source/isaaclab/test/envs/check_manager_based_env_anymal_locomotion.py b/source/isaaclab/test/envs/check_manager_based_env_anymal_locomotion.py index c6169c94d19..5bfeaa89eed 100644 --- a/source/isaaclab/test/envs/check_manager_based_env_anymal_locomotion.py +++ b/source/isaaclab/test/envs/check_manager_based_env_anymal_locomotion.py @@ -203,11 +203,11 @@ 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 # 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 def main(): diff --git a/source/isaaclab/test/envs/check_manager_based_env_floating_cube.py b/source/isaaclab/test/envs/check_manager_based_env_floating_cube.py index fb7622ae67c..b2dfb8081e0 100644 --- a/source/isaaclab/test/envs/check_manager_based_env_floating_cube.py +++ b/source/isaaclab/test/envs/check_manager_based_env_floating_cube.py @@ -225,7 +225,7 @@ def __post_init__(self): # general settings self.decimation = 2 # simulation settings - self.sim.dt = 0.01 + self.sim.physics_manager_cfg.dt = 0.01 self.sim.physics_material = self.scene.terrain.physics_material diff --git a/source/isaaclab/test/envs/test_color_randomization.py b/source/isaaclab/test/envs/test_color_randomization.py index 6b4b004eb30..764baf0f2e1 100644 --- a/source/isaaclab/test/envs/test_color_randomization.py +++ b/source/isaaclab/test/envs/test_color_randomization.py @@ -131,7 +131,7 @@ def __post_init__(self): # step settings self.decimation = 4 # env step every 4 sim steps: 200Hz / 4 = 50Hz # simulation settings - self.sim.dt = 0.005 # sim step every 5ms: 200Hz + self.sim.physics_manager_cfg.dt = 0.005 # sim step every 5ms: 200Hz @pytest.mark.parametrize("device", ["cpu", "cuda"]) diff --git a/source/isaaclab/test/envs/test_env_rendering_logic.py b/source/isaaclab/test/envs/test_env_rendering_logic.py index a70ea672db6..2eed5d93aaa 100644 --- a/source/isaaclab/test/envs/test_env_rendering_logic.py +++ b/source/isaaclab/test/envs/test_env_rendering_logic.py @@ -174,7 +174,7 @@ 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 + assert env.sim.carb_settings.get("/isaaclab/has_gui") and bool(env.sim.carb_settings.get("/isaaclab/render/offscreen")) # add physics and render callbacks env.sim.add_physics_callback("physics_step", physics_cb) @@ -193,7 +193,7 @@ def test_env_rendering_logic(env_type, render_interval, physics_callback, render 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" + assert abs(physics_time - num_physics_steps * env.cfg.sim.physics_manager_cfg.dt) < 1e-6, "Physics time mismatch" # check that we have completed the correct number of rendering steps _, num_render_steps = get_render_stats() @@ -201,7 +201,7 @@ def test_env_rendering_logic(env_type, render_interval, physics_callback, render # 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 + abs(render_time - num_render_steps * env.cfg.sim.physics_manager_cfg.dt * env.cfg.sim.render_interval) < 1e-6 ), "Render time mismatch" # close the environment diff --git a/source/isaaclab/test/envs/test_manager_based_env.py b/source/isaaclab/test/envs/test_manager_based_env.py index 7ec9ef2d43f..6244461cb52 100644 --- a/source/isaaclab/test/envs/test_manager_based_env.py +++ b/source/isaaclab/test/envs/test_manager_based_env.py @@ -77,7 +77,7 @@ def __post_init__(self): # step settings self.decimation = 4 # env step every 4 sim steps: 200Hz / 4 = 50Hz # simulation settings - self.sim.dt = 0.005 # sim step every 5ms: 200Hz + self.sim.physics_manager_cfg.dt = 0.005 # sim step every 5ms: 200Hz self.sim.render_interval = self.decimation # render every 4 sim steps # pass device down from test self.sim.device = device @@ -103,7 +103,7 @@ def __post_init__(self): # step settings self.decimation = 4 # env step every 4 sim steps: 200Hz / 4 = 50Hz # simulation settings - self.sim.dt = 0.005 # sim step every 5ms: 200Hz + self.sim.physics_manager_cfg.dt = 0.005 # sim step every 5ms: 200Hz self.sim.render_interval = self.decimation # render every 4 sim steps # pass device down from test self.sim.device = device diff --git a/source/isaaclab/test/envs/test_manager_based_rl_env_ui.py b/source/isaaclab/test/envs/test_manager_based_rl_env_ui.py index f35c11a1c40..9b7e7030dbc 100644 --- a/source/isaaclab/test/envs/test_manager_based_rl_env_ui.py +++ b/source/isaaclab/test/envs/test_manager_based_rl_env_ui.py @@ -64,7 +64,7 @@ def __post_init__(self): # step settings self.decimation = 4 # env step every 4 sim steps: 200Hz / 4 = 50Hz # simulation settings - self.sim.dt = 0.005 # sim step every 5ms: 200Hz + self.sim.physics_manager_cfg.dt = 0.005 # sim step every 5ms: 200Hz self.sim.render_interval = self.decimation # render every 4 sim steps # pass device down from test self.sim.device = device diff --git a/source/isaaclab/test/envs/test_scale_randomization.py b/source/isaaclab/test/envs/test_scale_randomization.py index 42db1edb7fa..7e8c141d906 100644 --- a/source/isaaclab/test/envs/test_scale_randomization.py +++ b/source/isaaclab/test/envs/test_scale_randomization.py @@ -274,7 +274,7 @@ def __post_init__(self): # general settings self.decimation = 2 # simulation settings - self.sim.dt = 0.01 + self.sim.physics_manager_cfg.dt = 0.01 self.sim.physics_material = self.scene.terrain.physics_material self.sim.render_interval = self.decimation diff --git a/source/isaaclab/test/envs/test_texture_randomization.py b/source/isaaclab/test/envs/test_texture_randomization.py index d2e4903fae5..179b331fc3d 100644 --- a/source/isaaclab/test/envs/test_texture_randomization.py +++ b/source/isaaclab/test/envs/test_texture_randomization.py @@ -177,7 +177,7 @@ def __post_init__(self): # step settings self.decimation = 4 # env step every 4 sim steps: 200Hz / 4 = 50Hz # simulation settings - self.sim.dt = 0.005 # sim step every 5ms: 200Hz + self.sim.physics_manager_cfg.dt = 0.005 # sim step every 5ms: 200Hz @pytest.mark.parametrize("device", ["cpu", "cuda"]) diff --git a/source/isaaclab/test/managers/test_recorder_manager.py b/source/isaaclab/test/managers/test_recorder_manager.py index 1ba17f65b87..fab99ed02e2 100644 --- a/source/isaaclab/test/managers/test_recorder_manager.py +++ b/source/isaaclab/test/managers/test_recorder_manager.py @@ -118,7 +118,7 @@ def __post_init__(self): # step settings self.decimation = 4 # env step every 4 sim steps: 200Hz / 4 = 50Hz # simulation settings - self.sim.dt = 0.005 # sim step every 5ms: 200Hz + self.sim.physics_manager_cfg.dt = 0.005 # sim step every 5ms: 200Hz self.sim.render_interval = self.decimation # render every 4 sim steps # pass device down from test self.sim.device = device diff --git a/source/isaaclab/test/markers/check_markers_visibility.py b/source/isaaclab/test/markers/check_markers_visibility.py index 98dbee8ddcd..ac5c734994a 100644 --- a/source/isaaclab/test/markers/check_markers_visibility.py +++ b/source/isaaclab/test/markers/check_markers_visibility.py @@ -132,7 +132,7 @@ def main(): sim_cfg = sim_utils.SimulationCfg(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]) + sim._visualizer_interface.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) # design scene scene_cfg = SensorsSceneCfg(num_envs=args_cli.num_envs, env_spacing=2.0) scene = InteractiveScene(scene_cfg) diff --git a/source/isaaclab/test/markers/test_visualization_markers.py b/source/isaaclab/test/markers/test_visualization_markers.py index 7183eb15a03..15615c4d5fd 100644 --- a/source/isaaclab/test/markers/test_visualization_markers.py +++ b/source/isaaclab/test/markers/test_visualization_markers.py @@ -15,7 +15,7 @@ import pytest import torch -from isaacsim.core.api.simulation_context import SimulationContext +from isaaclab.sim import SimulationContext import isaaclab.sim as sim_utils from isaaclab.markers import VisualizationMarkers, VisualizationMarkersCfg diff --git a/source/isaaclab/test/scene/check_interactive_scene.py b/source/isaaclab/test/scene/check_interactive_scene.py index 5b2463b315a..6fc8b4d7479 100644 --- a/source/isaaclab/test/scene/check_interactive_scene.py +++ b/source/isaaclab/test/scene/check_interactive_scene.py @@ -82,7 +82,7 @@ def main(): # Load kit helper sim = SimulationContext(sim_utils.SimulationCfg(dt=0.005)) # Set main camera - sim.set_camera_view(eye=[5, 5, 5], target=[0.0, 0.0, 0.0]) + sim._visualizer_interface.set_camera_view(eye=[5, 5, 5], target=[0.0, 0.0, 0.0]) # Spawn things into stage with Timer("Setup scene"): diff --git a/source/isaaclab/test/scene/test_interactive_scene.py b/source/isaaclab/test/scene/test_interactive_scene.py index 1a42a340baa..2eab9f3f070 100644 --- a/source/isaaclab/test/scene/test_interactive_scene.py +++ b/source/isaaclab/test/scene/test_interactive_scene.py @@ -67,8 +67,6 @@ def make_scene(num_envs: int, env_spacing: float = 1.0): yield make_scene, sim sim.stop() - sim.clear() - sim.clear_all_callbacks() sim.clear_instance() diff --git a/source/isaaclab/test/sensors/check_contact_sensor.py b/source/isaaclab/test/sensors/check_contact_sensor.py index c556e732658..56d1872e9f9 100644 --- a/source/isaaclab/test/sensors/check_contact_sensor.py +++ b/source/isaaclab/test/sensors/check_contact_sensor.py @@ -36,7 +36,7 @@ import torch -from isaacsim.core.api.simulation_context import SimulationContext +from isaaclab.sim import SimulationContext from isaacsim.core.cloner import GridCloner from isaacsim.core.utils.viewports import set_camera_view @@ -110,7 +110,7 @@ def main(): ) contact_sensor = ContactSensor(cfg=contact_sensor_cfg) # filter collisions within each environment instance - 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", envs_prim_paths, global_paths=["/World/defaultGroundPlane"] ) diff --git a/source/isaaclab/test/sensors/check_imu_sensor.py b/source/isaaclab/test/sensors/check_imu_sensor.py index 3616b296043..30b16ab0cbe 100644 --- a/source/isaaclab/test/sensors/check_imu_sensor.py +++ b/source/isaaclab/test/sensors/check_imu_sensor.py @@ -40,7 +40,7 @@ import traceback import omni -from isaacsim.core.api.simulation_context import SimulationContext +from isaaclab.sim import SimulationContext from isaacsim.core.cloner import GridCloner from isaacsim.core.utils.viewports import set_camera_view from pxr import PhysxSchema diff --git a/source/isaaclab/test/sensors/check_multi_mesh_ray_caster.py b/source/isaaclab/test/sensors/check_multi_mesh_ray_caster.py index 3d137ece466..07d60f96c9b 100644 --- a/source/isaaclab/test/sensors/check_multi_mesh_ray_caster.py +++ b/source/isaaclab/test/sensors/check_multi_mesh_ray_caster.py @@ -45,7 +45,7 @@ import random import torch -from isaacsim.core.api.simulation_context import SimulationContext +from isaaclab.sim import SimulationContext from isaacsim.core.cloner import GridCloner from isaacsim.core.prims import RigidPrim from isaacsim.core.utils.viewports import set_camera_view @@ -102,7 +102,7 @@ def design_scene(sim: SimulationContext, num_envs: int = 2048): cloner.define_base_env("/World/envs") envs_prim_paths = cloner.generate_paths("/World/envs/env", num_paths=num_envs) cloner.clone(source_prim_path="/World/envs/env_0", prim_paths=envs_prim_paths, replicate_physics=True) - 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"] ) diff --git a/source/isaaclab/test/sensors/check_ray_caster.py b/source/isaaclab/test/sensors/check_ray_caster.py index c2e12da4ea6..12d25aa0ebf 100644 --- a/source/isaaclab/test/sensors/check_ray_caster.py +++ b/source/isaaclab/test/sensors/check_ray_caster.py @@ -41,7 +41,7 @@ import torch -from isaacsim.core.api.simulation_context import SimulationContext +from isaaclab.sim import SimulationContext from isaacsim.core.cloner import GridCloner from isaacsim.core.prims import RigidPrim from isaacsim.core.utils.viewports import set_camera_view @@ -79,7 +79,7 @@ def design_scene(sim: SimulationContext, num_envs: int = 2048): cloner.define_base_env("/World/envs") envs_prim_paths = cloner.generate_paths("/World/envs/env", num_paths=num_envs) cloner.clone(source_prim_path="/World/envs/env_0", prim_paths=envs_prim_paths, replicate_physics=True) - 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"] ) diff --git a/source/isaaclab/test/sensors/test_camera.py b/source/isaaclab/test/sensors/test_camera.py index eb3bafa91cf..a8b9a02ce37 100644 --- a/source/isaaclab/test/sensors/test_camera.py +++ b/source/isaaclab/test/sensors/test_camera.py @@ -77,9 +77,8 @@ def teardown(sim: sim_utils.SimulationContext): 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_all_callbacks() 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.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") # Play sim sim.reset() # Check if camera is initialized @@ -127,7 +126,7 @@ def test_camera_init(setup_sim_camera): # perform rendering sim.step() # update camera - camera.update(sim.cfg.dt) + camera.update(sim.cfg.physics_manager_cfg.dt) # check image data for im_data in camera.data.output.values(): assert im_data.shape == (1, camera_cfg.height, camera_cfg.width, 1) diff --git a/source/isaaclab/test/sensors/test_frame_transformer.py b/source/isaaclab/test/sensors/test_frame_transformer.py index 725aa7d29fa..4a18bdc87c1 100644 --- a/source/isaaclab/test/sensors/test_frame_transformer.py +++ b/source/isaaclab/test/sensors/test_frame_transformer.py @@ -78,10 +78,9 @@ def sim(): # Load kit helper sim = sim_utils.SimulationContext(sim_utils.SimulationCfg(dt=0.005, device="cpu")) # Set main camera - sim.set_camera_view(eye=(5.0, 5.0, 5.0), target=(0.0, 0.0, 0.0)) + sim._visualizer_interface.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() diff --git a/source/isaaclab/test/sensors/test_imu.py b/source/isaaclab/test/sensors/test_imu.py index d221a182568..38736eef0bd 100644 --- a/source/isaaclab/test/sensors/test_imu.py +++ b/source/isaaclab/test/sensors/test_imu.py @@ -213,7 +213,6 @@ def setup_sim(): sim.reset() yield sim, scene # Cleanup - 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 bfe303ea751..1e46dc741d2 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 @@ -81,9 +81,8 @@ def setup_simulation(): 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_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 583791de79b..158752b9d3c 100644 --- a/source/isaaclab/test/sensors/test_multi_tiled_camera.py +++ b/source/isaaclab/test/sensors/test_multi_tiled_camera.py @@ -60,9 +60,8 @@ def setup_camera(): 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_all_callbacks() 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.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") # Play sim sim.reset() @@ -181,7 +180,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.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") # Play sim sim.reset() @@ -282,7 +281,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.carb_settings.get_as_bool("/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 319d3cbeed1..4967df35d27 100644 --- a/source/isaaclab/test/sensors/test_ray_caster_camera.py +++ b/source/isaaclab/test/sensors/test_ray_caster_camera.py @@ -84,9 +84,8 @@ def teardown(sim: sim_utils.SimulationContext): 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_all_callbacks() sim.clear_instance() diff --git a/source/isaaclab/test/sensors/test_sensor_base.py b/source/isaaclab/test/sensors/test_sensor_base.py index 2f21c05970c..dcd16939e44 100644 --- a/source/isaaclab/test/sensors/test_sensor_base.py +++ b/source/isaaclab/test/sensors/test_sensor_base.py @@ -108,9 +108,8 @@ def create_dummy_sensor(request, device): # 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_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 5d37143db22..b1176e07ea9 100644 --- a/source/isaaclab/test/sensors/test_tiled_camera.py +++ b/source/isaaclab/test/sensors/test_tiled_camera.py @@ -59,8 +59,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.clear_all_callbacks() + sim.stop() sim.clear_instance() @@ -72,7 +71,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.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") # Play sim sim.reset() # Check if camera is initialized @@ -251,7 +250,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.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") # Play sim sim.reset() # Check if camera is initialized @@ -308,7 +307,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.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") # Play sim sim.reset() # Check if camera is initialized @@ -410,7 +409,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.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") # Play sim sim.reset() # Check if camera is initialized @@ -464,7 +463,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.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") # Play sim sim.reset() # Check if camera is initialized @@ -518,7 +517,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.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") # Play sim sim.reset() # Check if camera is initialized @@ -572,7 +571,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.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") # Play sim sim.reset() # Check if camera is initialized @@ -626,7 +625,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.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") # Play sim sim.reset() # Check if camera is initialized @@ -683,7 +682,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.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") # Play sim sim.reset() # Check if camera is initialized @@ -737,7 +736,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.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") # Play sim sim.reset() # Check if camera is initialized @@ -792,7 +791,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.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") # Play sim sim.reset() # Check if camera is initialized @@ -847,7 +846,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.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") # Play sim sim.reset() # Check if camera is initialized @@ -903,7 +902,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.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") # Play sim sim.reset() # Check if camera is initialized @@ -960,7 +959,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.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") # Play sim sim.reset() # Check if camera is initialized @@ -1015,7 +1014,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.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") # Play sim sim.reset() # Check if camera is initialized @@ -1083,7 +1082,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.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") # Play sim sim.reset() # Check if camera is initialized @@ -1185,7 +1184,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.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") # Play sim sim.reset() # Check if camera is initialized @@ -1285,7 +1284,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.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") # Play sim sim.reset() # Check if camera is initialized @@ -1405,7 +1404,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.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") # Play sim sim.reset() # Check if camera is initialized diff --git a/source/isaaclab/test/sim/check_meshes.py b/source/isaaclab/test/sim/check_meshes.py index c99f56ec820..9771330fcce 100644 --- a/source/isaaclab/test/sim/check_meshes.py +++ b/source/isaaclab/test/sim/check_meshes.py @@ -143,7 +143,7 @@ def main(): sim_cfg = sim_utils.SimulationCfg(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]) + sim._visualizer_interface.set_camera_view([8.0, 8.0, 6.0], [0.0, 0.0, 0.0]) # Design scene by adding assets to it design_scene() 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 e592a7abea6..a52dd0ae5f7 100644 --- a/source/isaaclab/test/sim/test_build_simulation_context_headless.py +++ b/source/isaaclab/test/sim/test_build_simulation_context_headless.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 # Ensure that dome light didn't get added automatically as we are headless assert not sim.stage.GetPrimAtPath("/World/defaultDomeLight").IsValid() @@ -86,6 +86,6 @@ def test_build_simulation_context_cfg(): ) with build_simulation_context(sim_cfg=cfg, gravity_enabled=False, dt=0.01, device="cpu") as sim: - assert sim.cfg.gravity == gravity + 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 08107020683..1e19f526850 100644 --- a/source/isaaclab/test/sim/test_build_simulation_context_nonheadless.py +++ b/source/isaaclab/test/sim/test_build_simulation_context_nonheadless.py @@ -32,12 +32,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]) @@ -78,6 +78,6 @@ def test_build_simulation_context_cfg(): ) with build_simulation_context(sim_cfg=cfg, gravity_enabled=False, dt=0.01, device="cpu") as sim: - assert sim.cfg.gravity == gravity + 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_mesh_converter.py b/source/isaaclab/test/sim/test_mesh_converter.py index f3d73f92e59..498cd0cff36 100644 --- a/source/isaaclab/test/sim/test_mesh_converter.py +++ b/source/isaaclab/test/sim/test_mesh_converter.py @@ -19,7 +19,7 @@ import tempfile import omni -from isaacsim.core.api.simulation_context import SimulationContext +from isaaclab.sim import SimulationContext from pxr import UsdGeom, UsdPhysics import isaaclab.sim as sim_utils @@ -70,8 +70,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 211cf4e6b92..f67df0d0fd7 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 isaacsim.core.api.simulation_context import SimulationContext +from isaaclab.sim import SimulationContext from isaacsim.core.utils.extensions import enable_extension, get_extension_path_from_name import isaaclab.sim as sim_utils @@ -47,8 +47,6 @@ def test_setup_teardown(): # Teardown: Cleanup simulation sim.stop() - sim.clear() - sim.clear_all_callbacks() sim.clear_instance() diff --git a/source/isaaclab/test/sim/test_schemas.py b/source/isaaclab/test/sim/test_schemas.py index a89d4dcb534..919cd3a0127 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 isaacsim.core.api.simulation_context import SimulationContext +from isaaclab.sim import SimulationContext from pxr import UsdPhysics import isaaclab.sim as sim_utils @@ -74,8 +74,6 @@ def setup_simulation(): yield sim, arti_cfg, rigid_cfg, collision_cfg, mass_cfg, joint_cfg # Teardown sim.stop() - sim.clear() - sim.clear_all_callbacks() sim.clear_instance() diff --git a/source/isaaclab/test/sim/test_simulation_context.py b/source/isaaclab/test/sim/test_simulation_context.py index a9072839e87..1efcbd7e7e6 100644 --- a/source/isaaclab/test/sim/test_simulation_context.py +++ b/source/isaaclab/test/sim/test_simulation_context.py @@ -12,47 +12,94 @@ """Rest everything follows.""" +import builtins import numpy as np import pytest -from collections.abc import Generator +import weakref -import omni.physx -from isaacsim.core.api.simulation_context import SimulationContext as IsaacSimulationContext +import omni.timeline import isaaclab.sim as sim_utils from isaaclab.sim import SimulationCfg, SimulationContext +from isaaclab.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) +""" +Basic Configuration Tests +""" + + +@pytest.mark.isaacsim_ci +@pytest.mark.parametrize("device", ["cuda:0", "cpu"]) +def test_init(device): + """Test the simulation context initialization.""" + from isaaclab.sim.spawners.materials import RigidBodyMaterialCfg + + 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) - # 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() + + # 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 + 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 = ( + physics_scene.GetGravityDirectionAttr().Get(), + physics_scene.GetGravityMagnitudeAttr().Get(), + ) + gravity = np.array(gravity_dir) * gravity_mag + np.testing.assert_almost_equal(gravity, cfg.physics_manager_cfg.gravity) + + +@pytest.mark.isaacsim_ci +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 @@ -60,43 +107,22 @@ def test_singleton(): """Tests that the singleton is working.""" sim1 = SimulationContext() sim2 = SimulationContext() - sim3 = IsaacSimulationContext() assert sim1 is sim2 - assert sim1 is sim3 # try to delete the singleton sim2.clear_instance() assert sim1.instance() is None # create new instance - sim4 = SimulationContext() - assert sim1 is not sim4 - assert sim3 is not sim4 - assert sim1.instance() is sim4.instance() - assert sim3.instance() is sim4.instance() + sim3 = SimulationContext() + assert sim1 is not sim3 + assert sim1.instance() is sim3.instance() # clear instance sim3.clear_instance() -@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) - # TODO: Figure out why keyword argument doesn't work. - # note: added a fix in Isaac Sim 2023.1 for this. - # sim = SimulationContext(cfg=cfg) - - # 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() - # 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 = np.array(gravity_dir) * gravity_mag - np.testing.assert_almost_equal(gravity, cfg.gravity) +""" +Property Tests. +""" @pytest.mark.isaacsim_ci @@ -125,45 +151,982 @@ 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_interface.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/physics/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 + 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 + 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 in callbacks during reset are properly captured and 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) + + # create a callback that raises an exception + def on_physics_ready_with_exception(event): + try: + raise RuntimeError("Test exception in callback during reset!") + except Exception as e: + builtins.ISAACLAB_CALLBACK_EXCEPTION = e # type: ignore + + # register callback that will raise an exception + callback_id = PhysxManager.register_callback( + lambda event: on_physics_ready_with_exception(event), event=IsaacEvents.PHYSICS_READY + ) + + try: + # reset should capture and re-raise the exception + with pytest.raises(RuntimeError, match="Test exception in callback during reset!"): + sim.reset() + + # verify the exception was cleared after being raised + assert builtins.ISAACLAB_CALLBACK_EXCEPTION is None # type: ignore + + finally: + # cleanup callback + if callback_id is not None: + PhysxManager.deregister_callback(callback_id) + # ensure exception is cleared + builtins.ISAACLAB_CALLBACK_EXCEPTION = None # type: ignore + + +@pytest.mark.isaacsim_ci +def test_exception_in_callback_on_play(): + """Test that exceptions in callbacks during play are properly captured and raised.""" + + cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01)) + sim = SimulationContext(cfg) + + # create callback tracker + callback_state = {"called": False} + + def on_play_with_exception(event): + try: + callback_state["called"] = True + raise ValueError("Test exception in play callback!") + except Exception as e: + builtins.ISAACLAB_CALLBACK_EXCEPTION = e # type: ignore + + # register callback via timeline + 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_with_exception(event), order=20 + ) + + try: + # play should capture and re-raise the exception + with pytest.raises(ValueError, match="Test exception in play callback!"): + sim.play() + + # verify callback was called + assert callback_state["called"] + + # verify the exception was cleared + assert builtins.ISAACLAB_CALLBACK_EXCEPTION is None # type: ignore + + finally: + # cleanup + if play_handle is not None: + play_handle.unsubscribe() + # ensure exception is cleared + builtins.ISAACLAB_CALLBACK_EXCEPTION = None # type: ignore + + +@pytest.mark.isaacsim_ci +def test_exception_in_callback_on_stop(): + """Test that exceptions in callbacks during stop are properly captured and raised.""" + + cfg = SimulationCfg(physics_manager_cfg=PhysxManagerCfg(dt=0.01)) + sim = SimulationContext(cfg) + + # start the simulation first + sim.play() + + def on_stop_with_exception(event): + try: + raise OSError("Test exception in stop callback!") + except Exception as e: + builtins.ISAACLAB_CALLBACK_EXCEPTION = e # type: ignore + + # register callback via timeline + timeline_event_stream = omni.timeline.get_timeline_interface().get_timeline_event_stream() + stop_handle = timeline_event_stream.create_subscription_to_pop_by_type( + int(omni.timeline.TimelineEventType.STOP), lambda event: on_stop_with_exception(event), order=20 + ) + + try: + # disable app control to prevent hanging + sim._disable_app_control_on_stop_handle = True # type: ignore + + # stop should capture and re-raise the exception + with pytest.raises(OSError, match="Test exception in stop callback!"): + sim.stop() + + # verify the exception was cleared + assert builtins.ISAACLAB_CALLBACK_EXCEPTION is None # type: ignore + + finally: + # cleanup + if stop_handle is not None: + stop_handle.unsubscribe() + # ensure exception is cleared + builtins.ISAACLAB_CALLBACK_EXCEPTION = None # type: ignore 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 3cf15126621..59c9d73ae32 100644 --- a/source/isaaclab/test/sim/test_simulation_stage_in_memory.py +++ b/source/isaaclab/test/sim/test_simulation_stage_in_memory.py @@ -39,9 +39,9 @@ def sim(): yield sim omni.physx.get_physx_simulation_interface().detach_stage() sim.stop() - sim.clear() - sim.clear_all_callbacks() sim.clear_instance() + # Create a new stage in the USD context to ensure subsequent tests have a valid context stage + sim_utils.create_new_stage() """ @@ -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): @@ -68,16 +68,9 @@ def test_stage_in_memory_with_shapes(sim): cfg = sim_utils.MultiAssetSpawnerCfg( assets_cfg=[ - sim_utils.ConeCfg( - radius=0.3, - height=0.6, - ), - sim_utils.CuboidCfg( - size=(0.3, 0.3, 0.3), - ), - sim_utils.SphereCfg( - radius=0.3, - ), + sim_utils.ConeCfg(radius=0.3, height=0.6), + sim_utils.CuboidCfg(size=(0.3, 0.3, 0.3)), + sim_utils.SphereCfg(radius=0.3), ], random_choice=True, rigid_props=sim_utils.RigidBodyPropertiesCfg( @@ -128,7 +121,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): @@ -190,7 +183,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 293642a15d2..7a095b2ce2d 100644 --- a/source/isaaclab/test/sim/test_spawn_from_files.py +++ b/source/isaaclab/test/sim/test_spawn_from_files.py @@ -16,7 +16,7 @@ from packaging.version import Version import omni.kit.app -from isaacsim.core.api.simulation_context import SimulationContext +from isaaclab.sim import SimulationContext import isaaclab.sim as sim_utils from isaaclab.utils.assets import ISAACLAB_NUCLEUS_DIR @@ -39,8 +39,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 325cd06866e..6b6b4b7dce1 100644 --- a/source/isaaclab/test/sim/test_spawn_lights.py +++ b/source/isaaclab/test/sim/test_spawn_lights.py @@ -15,7 +15,7 @@ import pytest -from isaacsim.core.api.simulation_context import SimulationContext +from isaaclab.sim import SimulationContext from pxr import Usd, UsdLux import isaaclab.sim as sim_utils @@ -39,8 +39,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 ee8cb38f90a..162f57f2fc3 100644 --- a/source/isaaclab/test/sim/test_spawn_materials.py +++ b/source/isaaclab/test/sim/test_spawn_materials.py @@ -15,7 +15,7 @@ import pytest -from isaacsim.core.api.simulation_context import SimulationContext +from isaaclab.sim import SimulationContext from pxr import UsdPhysics, UsdShade import isaaclab.sim as sim_utils @@ -31,8 +31,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 66a48422c0c..25221b91e8f 100644 --- a/source/isaaclab/test/sim/test_spawn_meshes.py +++ b/source/isaaclab/test/sim/test_spawn_meshes.py @@ -15,7 +15,7 @@ import pytest -from isaacsim.core.api.simulation_context import SimulationContext +from isaaclab.sim import SimulationContext import isaaclab.sim as sim_utils @@ -34,8 +34,7 @@ def sim(): yield sim # Cleanup sim.stop() - sim.clear() - sim.clear_all_callbacks() + () sim.clear_instance() diff --git a/source/isaaclab/test/sim/test_spawn_sensors.py b/source/isaaclab/test/sim/test_spawn_sensors.py index 320a47b3336..3606baa7df3 100644 --- a/source/isaaclab/test/sim/test_spawn_sensors.py +++ b/source/isaaclab/test/sim/test_spawn_sensors.py @@ -15,7 +15,7 @@ import pytest -from isaacsim.core.api.simulation_context import SimulationContext +from isaaclab.sim import SimulationContext from pxr import Usd import isaaclab.sim as sim_utils @@ -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_shapes.py b/source/isaaclab/test/sim/test_spawn_shapes.py index ed7ba68f89b..b86c343f62a 100644 --- a/source/isaaclab/test/sim/test_spawn_shapes.py +++ b/source/isaaclab/test/sim/test_spawn_shapes.py @@ -14,7 +14,7 @@ import pytest -from isaacsim.core.api.simulation_context import SimulationContext +from isaaclab.sim import SimulationContext import isaaclab.sim as sim_utils @@ -28,8 +28,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_wrappers.py b/source/isaaclab/test/sim/test_spawn_wrappers.py index 3dd07a54e6f..ed9366e9681 100644 --- a/source/isaaclab/test/sim/test_spawn_wrappers.py +++ b/source/isaaclab/test/sim/test_spawn_wrappers.py @@ -15,7 +15,7 @@ import pytest -from isaacsim.core.api.simulation_context import SimulationContext +from isaaclab.sim import SimulationContext import isaaclab.sim as sim_utils from isaaclab.utils.assets import ISAACLAB_NUCLEUS_DIR @@ -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 f12a7515fb2..089728330bd 100644 --- a/source/isaaclab/test/sim/test_urdf_converter.py +++ b/source/isaaclab/test/sim/test_urdf_converter.py @@ -18,7 +18,7 @@ from packaging.version import Version import omni.kit.app -from isaacsim.core.api.simulation_context import SimulationContext +from isaaclab.sim import SimulationContext from isaacsim.core.prims import Articulation import isaaclab.sim as sim_utils @@ -56,8 +56,6 @@ def sim_config(): yield sim, config # Teardown sim.stop() - sim.clear() - sim.clear_all_callbacks() sim.clear_instance() diff --git a/source/isaaclab/test/terrains/check_terrain_importer.py b/source/isaaclab/test/terrains/check_terrain_importer.py index fdc305a07af..e85d960f0d5 100644 --- a/source/isaaclab/test/terrains/check_terrain_importer.py +++ b/source/isaaclab/test/terrains/check_terrain_importer.py @@ -69,7 +69,7 @@ from isaacsim.core.api.materials import PhysicsMaterial from isaacsim.core.api.materials.preview_surface import PreviewSurface from isaacsim.core.api.objects import DynamicSphere -from isaacsim.core.api.simulation_context import SimulationContext +from isaaclab.sim import SimulationContext from isaacsim.core.cloner import GridCloner from isaacsim.core.prims import RigidPrim, SingleGeometryPrim, SingleRigidPrim from isaacsim.core.utils.extensions import enable_extension @@ -158,7 +158,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.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"] ) diff --git a/source/isaaclab/test/terrains/test_terrain_importer.py b/source/isaaclab/test/terrains/test_terrain_importer.py index 63d9230560b..17e4cdf733c 100644 --- a/source/isaaclab/test/terrains/test_terrain_importer.py +++ b/source/isaaclab/test/terrains/test_terrain_importer.py @@ -317,7 +317,7 @@ 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"] ) diff --git a/source/isaaclab/test/visualization/check_scene_xr_visualization.py b/source/isaaclab/test/visualization/check_scene_xr_visualization.py index 11fe31998dd..2d43d54b3de 100644 --- a/source/isaaclab/test/visualization/check_scene_xr_visualization.py +++ b/source/isaaclab/test/visualization/check_scene_xr_visualization.py @@ -238,7 +238,7 @@ def main(): sim_cfg = sim_utils.SimulationCfg(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)) + sim._visualizer_interface.set_camera_view(eye=(8, 0, 4), target=(0.0, 0.0, 0.0)) # design scene scene = InteractiveScene(SimpleSceneCfg(num_envs=args_cli.num_envs, env_spacing=2.0)) # Play the simulator diff --git a/source/isaaclab_mimic/isaaclab_mimic/locomanipulation_sdg/envs/g1_locomanipulation_sdg_env.py b/source/isaaclab_mimic/isaaclab_mimic/locomanipulation_sdg/envs/g1_locomanipulation_sdg_env.py index 052039480a4..28bd1594bf1 100644 --- a/source/isaaclab_mimic/isaaclab_mimic/locomanipulation_sdg/envs/g1_locomanipulation_sdg_env.py +++ b/source/isaaclab_mimic/isaaclab_mimic/locomanipulation_sdg/envs/g1_locomanipulation_sdg_env.py @@ -130,7 +130,7 @@ def __post_init__(self): self.decimation = 4 self.episode_length_s = 100.0 # simulation settings - self.sim.dt = 1 / 200 # 200Hz + self.sim.physics_manager_cfg.dt = 1 / 200 # 200Hz self.sim.render_interval = 6 # Set the URDF and mesh paths for the IK controller @@ -144,7 +144,7 @@ class G1LocomanipulationSDGEnv(LocomanipulationSDGEnv): def __init__(self, cfg: G1LocomanipulationSDGEnvCfg, **kwargs): super().__init__(cfg) - self.sim.set_camera_view([10.5, 10.5, 10.5], [0.0, 0.0, 0.5]) + self.sim._visualizer_interface.set_camera_view([10.5, 10.5, 10.5], [0.0, 0.0, 0.5]) self._upper_body_dim = self.action_manager.get_term("upper_body_ik").action_dim self._waist_dim = 0 # self._env.action_manager.get_term("waist_joint_pos").action_dim self._lower_body_dim = self.action_manager.get_term("lower_body_joint_pos").action_dim 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 22130288757..26b438928b6 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/automate/assembly_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/automate/assembly_env.py @@ -822,7 +822,7 @@ def randomize_held_initial_state(self, env_ids, pre_grasp): def randomize_initial_state(self, env_ids): """Randomize initial state and perform any episode-level randomization.""" # Disable gravity. - physics_sim_view = sim_utils.SimulationContext.instance().physics_sim_view + physics_sim_view = sim_utils.SimulationContext.instance()._physics_interface.physics_sim_view physics_sim_view.set_gravity(carb.Float3(0.0, 0.0, 0.0)) self.randomize_fixed_initial_state(env_ids) 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 b78c80a71b9..ec7cf29d70c 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/automate/disassembly_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/automate/disassembly_env.py @@ -570,7 +570,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.carb_settings.get_as_bool("/isaaclab/render/rtx_sensors") # perform physics stepping for _ in range(self.cfg.decimation): self._sim_step_counter += 1 @@ -689,7 +689,7 @@ def close_gripper(self, env_ids): def randomize_initial_state(self, env_ids): """Randomize initial state and perform any episode-level randomization.""" # Disable gravity. - physics_sim_view = sim_utils.SimulationContext.instance().physics_sim_view + physics_sim_view = sim_utils.SimulationContext.instance()._physics_interface.physics_sim_view physics_sim_view.set_gravity(carb.Float3(0.0, 0.0, 0.0)) self.randomize_fixed_initial_state(env_ids) diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/factory/factory_env.py b/source/isaaclab_tasks/isaaclab_tasks/direct/factory/factory_env.py index a4e9c6d9ece..2356553c27f 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/factory/factory_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/factory/factory_env.py @@ -614,7 +614,7 @@ def step_sim_no_action(self): def randomize_initial_state(self, env_ids): """Randomize initial state and perform any episode-level randomization.""" # Disable gravity. - physics_sim_view = sim_utils.SimulationContext.instance().physics_sim_view + physics_sim_view = sim_utils.SimulationContext.instance()._physics_interface.physics_sim_view physics_sim_view.set_gravity(carb.Float3(0.0, 0.0, 0.0)) # (1.) Randomize fixed asset pose. 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 8b87e1bdb25..8a096a2a41a 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 @@ -189,7 +189,7 @@ def get_env_local_pose(env_pos: torch.Tensor, xformable: UsdGeom.Xformable, devi return torch.tensor([px, py, pz, qw, qx, qy, qz], device=device) - self.dt = self.cfg.sim.dt * self.cfg.decimation + self.dt = self.cfg.sim.physics_manager_cfg.dt * self.cfg.decimation # create auxiliary variables for computing applied action, observations and rewards self.robot_dof_lower_limits = self._robot.data.soft_joint_pos_limits[0, :, 0].to(device=self.device) diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/locomotion/locomotion_env.py b/source/isaaclab_tasks/isaaclab_tasks/direct/locomotion/locomotion_env.py index faac10e1a71..895bc312d1f 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/locomotion/locomotion_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/locomotion/locomotion_env.py @@ -102,7 +102,7 @@ def _compute_intermediate_values(self): self.basis_vec1, self.potentials, self.prev_potentials, - self.cfg.sim.dt, + self.cfg.sim.physics_manager_cfg.dt, ) def _get_observations(self) -> dict: @@ -169,7 +169,7 @@ def _reset_idx(self, env_ids: torch.Tensor | None): to_target = self.targets[env_ids] - default_root_state[:, :3] to_target[:, 2] = 0.0 - self.potentials[env_ids] = -torch.norm(to_target, p=2, dim=-1) / self.cfg.sim.dt + self.potentials[env_ids] = -torch.norm(to_target, p=2, dim=-1) / self.cfg.sim.physics_manager_cfg.dt self._compute_intermediate_values() 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 b3a6b5b9d25..3bebee57236 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/quadcopter/quadcopter_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/quadcopter/quadcopter_env.py @@ -125,7 +125,7 @@ def __init__(self, cfg: QuadcopterEnvCfg, render_mode: str | None = None, **kwar # Get specific body indices self._body_id = self._robot.find_bodies("body")[0] self._robot_mass = self._robot.root_physx_view.get_masses()[0].sum() - self._gravity_magnitude = torch.tensor(self.sim.cfg.gravity, device=self.device).norm() + self._gravity_magnitude = torch.tensor(self.sim.cfg.physics_manager_cfg.gravity, device=self.device).norm() self._robot_weight = (self._robot_mass * self._gravity_magnitude).item() # add handle for debug visualization (this is set to a valid handle inside set_debug_vis) 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/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 2c896bc604f..4f08cd00743 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 e74baaf0d0d..739d99480dc 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 a431b32657c..c8809563992 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 23b853691a0..272e34f1563 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 @@ -317,7 +317,7 @@ 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 @@ -325,7 +325,7 @@ def __post_init__(self): self.sim.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..cc551c8e547 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.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 85b7e5ae9ba..b29bd75285a 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,8 @@ 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.2 + 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 f0a139607c0..6c3b5b7247a 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 @@ -275,7 +275,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/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 3f521362a8a..0aa4c458419 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 @@ -422,11 +422,11 @@ 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.2 + 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 71594ae210d..8f5fd4b6d6c 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 @@ -340,7 +340,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 b2758f06a81..94952d3ef3d 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 @@ -230,10 +230,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 272661bda61..f2b2eaf9468 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 @@ -212,11 +212,11 @@ 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.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 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 1aceb299621..90a37e299ea 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 @@ -320,7 +320,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 abac9493a90..aa613d6e94a 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 @@ -355,7 +355,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 169fc08cb42..35783824aca 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 @@ -373,7 +373,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 23ed8d984bc..90302e57403 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 8d67478cc5e..4797b4043e1 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 @@ -365,7 +365,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 224c19adbf6..a048f1e789a 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,11 @@ 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.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 # 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.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 2cad32da6b1..da0b984fb17 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 @@ -275,7 +275,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 ed9bcbfc08b..907b41b9e69 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 bad88b401c7..2410a2ef95c 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 e36a5407402..782fba534d3 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 @@ -59,7 +59,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 976f14f6802..e6782d6caa4 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 @@ -129,7 +129,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 5c772a11760..14c45a5535b 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,11 @@ 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.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 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 526297b9561..252cba9cda0 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,11 @@ 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.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 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): diff --git a/source/isaaclab_tasks/isaaclab_tasks/utils/parse_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/utils/parse_cfg.py index 57675039d70..d8e1fc47949 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/utils/parse_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/utils/parse_cfg.py @@ -148,7 +148,7 @@ def parse_env_cfg( cfg.sim.device = device # disable fabric to read/write through USD if use_fabric is not None: - cfg.sim.use_fabric = use_fabric + cfg.sim.physics_manager_cfg.use_fabric = use_fabric # number of environments if num_envs is not None: cfg.scene.num_envs = num_envs diff --git a/source/isaaclab_tasks/test/env_test_utils.py b/source/isaaclab_tasks/test/env_test_utils.py index 43973e8994a..fc758852f61 100644 --- a/source/isaaclab_tasks/test/env_test_utils.py +++ b/source/isaaclab_tasks/test/env_test_utils.py @@ -12,8 +12,10 @@ import torch import carb +import omni.physx import omni.usd +import isaaclab.sim as sim_utils from isaaclab.envs.utils.spaces import sample_space from isaaclab.utils.version import get_isaac_sim_version @@ -182,12 +184,17 @@ def _check_random_actions( create_stage_in_memory: Whether to create stage in memory. disable_clone_in_fabric: Whether to disable fabric cloning. """ + # Import here to use in exception handler + from isaaclab.sim import SimulationContext + # create a new context stage, if stage in memory is not enabled if not create_stage_in_memory: omni.usd.get_context().new_stage() # 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) @@ -208,59 +215,67 @@ 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() - 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}" + 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}" + + # close environment + env.close() + + # Create a new stage in the USD context to ensure subsequent tests have a valid context stage + # This is necessary when using stage in memory, as the in-memory stage is destroyed on close + if create_stage_in_memory: + sim_utils.create_new_stage() - # close environment - env.close() + except Exception as e: + # try to close environment on exception + if env is not None and hasattr(env, "_is_closed"): + env.close() + elif hasattr(e, "obj") and hasattr(e.obj, "_is_closed"): + e.obj.close() + else: + # Ensure simulation context is cleared even if env creation failed + SimulationContext.clear_instance() + + pytest.fail(f"Failed to set-up the environment for task {task_name}. Error: {e}") def _check_valid_tensor(data: torch.Tensor | dict) -> bool: