From 46e5eb59e9a44b71c596c4c0ac28a371391867fb Mon Sep 17 00:00:00 2001 From: Matthew Trepte Date: Tue, 24 Mar 2026 19:39:20 +0000 Subject: [PATCH 01/11] move branch --- .../isaaclab/sim/simulation_context.py | 3 +++ source/isaaclab/setup.py | 1 + .../test_simulation_context_visualizers.py | 12 +++++++++++ .../kit/kit_visualizer.py | 20 ++++++++----------- 4 files changed, 24 insertions(+), 12 deletions(-) diff --git a/source/isaaclab/isaaclab/sim/simulation_context.py b/source/isaaclab/isaaclab/sim/simulation_context.py index 27e41f69a8b8..a82b3c662d16 100644 --- a/source/isaaclab/isaaclab/sim/simulation_context.py +++ b/source/isaaclab/isaaclab/sim/simulation_context.py @@ -694,6 +694,9 @@ def update_visualizers(self, dt: float) -> None: visualizers_to_remove.append(viz) continue if viz.is_rendering_paused(): + # Keep visualizer event loops responsive while rendering is paused + # so UI controls (e.g. "Resume Rendering") remain interactive. + viz.step(0.0) continue while viz.is_training_paused() and viz.is_running(): viz.step(0.0) diff --git a/source/isaaclab/setup.py b/source/isaaclab/setup.py index 2bbdcac07f4d..e2d566e80cc8 100644 --- a/source/isaaclab/setup.py +++ b/source/isaaclab/setup.py @@ -22,6 +22,7 @@ "torch>=2.10", "onnx>=1.18.0", # 1.16.2 throws access violation on Windows "prettytable==3.3.0", + "munch", "toml", # devices "hidapi==0.14.0.post2", diff --git a/source/isaaclab/test/sim/test_simulation_context_visualizers.py b/source/isaaclab/test/sim/test_simulation_context_visualizers.py index f0a1294d2b4a..024fba22cc29 100644 --- a/source/isaaclab/test/sim/test_simulation_context_visualizers.py +++ b/source/isaaclab/test/sim/test_simulation_context_visualizers.py @@ -136,10 +136,22 @@ def test_update_visualizers_removes_closed_nonrunning_and_failed(caplog): assert stopped_viz.close_calls == 1 assert failing_viz.close_calls == 1 assert paused_viz.close_calls == 0 + assert paused_viz.step_calls == [0.0] assert healthy_viz.step_calls == [0.1] assert any("Error stepping visualizer" in r.message for r in caplog.records) +def test_update_visualizers_keeps_rendering_paused_visualizer_ui_responsive(): + provider = _FakeProvider() + paused_viz = _FakeVisualizer(rendering_paused=True) + ctx = _make_context([paused_viz], provider=provider) + + ctx.update_visualizers(0.3) + + # Rendering-paused visualizers still receive zero-dt ticks to keep UI callbacks alive. + assert paused_viz.step_calls == [0.0] + + def test_update_visualizers_handles_training_pause_loop(): provider = _FakeProvider() viz = _FakeVisualizer(training_paused_steps=1) diff --git a/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualizer.py b/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualizer.py index 6b1b5c2077dc..47ea1e75c883 100644 --- a/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualizer.py +++ b/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualizer.py @@ -105,16 +105,10 @@ def step(self, dt: float) -> None: try: import omni.kit.app - from isaaclab.app.settings_manager import get_settings_manager - app = omni.kit.app.get_app() if app is not None and app.is_running(): - # Keep app pumping for viewport/UI updates only. - # Simulation stepping is owned by SimulationContext. - settings = get_settings_manager() - settings.set_bool("/app/player/playSimulations", False) + # Pump Kit/UI events only; SimulationContext owns physics stepping. app.update() - settings.set_bool("/app/player/playSimulations", True) except (ImportError, AttributeError) as exc: logger.debug("[KitVisualizer] App update skipped: %s", exc) @@ -148,13 +142,15 @@ def is_running(self) -> bool: return False def is_training_paused(self) -> bool: - """Return whether simulation play flag is paused in Kit settings.""" + """Return whether Kit timeline transport is paused.""" try: - from isaaclab.app.settings_manager import get_settings_manager + import omni.timeline - settings = get_settings_manager() - play_flag = settings.get("/app/player/playSimulations") - return play_flag is False + timeline = omni.timeline.get_timeline_interface() + if timeline is None: + return False + # Pause is transport state that is neither playing nor stopped. + return (not timeline.is_playing()) and (not timeline.is_stopped()) except Exception: return False From 88332254831e8ffdfeef18936eb08e0ac980f191 Mon Sep 17 00:00:00 2001 From: Matthew Trepte Date: Tue, 24 Mar 2026 20:08:51 +0000 Subject: [PATCH 02/11] speedup tests --- .../test/test_visualizer_smoke_logs.py | 125 +++++++++++++++++- 1 file changed, 124 insertions(+), 1 deletion(-) diff --git a/source/isaaclab_visualizers/test/test_visualizer_smoke_logs.py b/source/isaaclab_visualizers/test/test_visualizer_smoke_logs.py index 22f620fb02a8..8ac9e1f06ea1 100644 --- a/source/isaaclab_visualizers/test/test_visualizer_smoke_logs.py +++ b/source/isaaclab_visualizers/test/test_visualizer_smoke_logs.py @@ -12,7 +12,9 @@ import logging import socket +import copy +import numpy as np import pytest import torch from isaaclab_visualizers.kit import KitVisualizer, KitVisualizerCfg @@ -25,6 +27,8 @@ from isaaclab.scene import InteractiveSceneCfg from isaaclab.sim import SimulationCfg, SimulationContext from isaaclab.utils import configclass +from isaaclab_tasks.direct.cartpole.cartpole_camera_env import CartpoleCameraEnv +from isaaclab_tasks.direct.cartpole.cartpole_camera_presets_env_cfg import CartpoleCameraPresetsEnvCfg from isaaclab_tasks.manager_based.classic.cartpole.cartpole_env_cfg import ( CartpolePhysicsCfg, @@ -35,6 +39,7 @@ ASSERT_VISUALIZER_WARNINGS = True _SMOKE_STEPS = 4 +_MAX_NON_BLACK_STEPS = max(_SMOKE_STEPS, 8) _VIS_LOGGER_PREFIXES = ( "isaaclab.visualizers", "isaaclab_visualizers", @@ -93,7 +98,8 @@ def _get_visualizer_cfg(visualizer_kind: str): if visualizer_kind == "viser": __import__("newton") __import__("viser") - return ViserVisualizerCfg(open_browser=False), ViserVisualizer + port = _find_free_tcp_port(host="127.0.0.1") + return ViserVisualizerCfg(open_browser=False, port=port), ViserVisualizer if visualizer_kind == "rerun": __import__("newton") __import__("rerun") @@ -151,6 +157,71 @@ def _get_physics_cfg(backend_kind: str): raise ValueError(f"Unknown backend: {backend_kind!r}") +def _assert_non_black_tensor(image_tensor: torch.Tensor, *, min_nonzero_pixels: int = 1) -> None: + """Assert camera-like tensor contains non-black pixels.""" + assert isinstance(image_tensor, torch.Tensor), f"Expected torch.Tensor, got {type(image_tensor)!r}" + assert image_tensor.numel() > 0, "Image tensor is empty." + finite_tensor = torch.where(torch.isfinite(image_tensor), image_tensor, torch.zeros_like(image_tensor)) + if finite_tensor.dtype.is_floating_point: + nonzero = torch.count_nonzero(torch.abs(finite_tensor) > 1e-6).item() + else: + nonzero = torch.count_nonzero(finite_tensor > 0).item() + assert nonzero >= min_nonzero_pixels, "Rendered frame appears black (no non-zero pixels)." + + +def _assert_non_black_frame_array(frame) -> None: + """Assert viewer-captured frame has visible, non-black content.""" + frame_arr = np.asarray(frame) + assert frame_arr.size > 0, "Viewer returned an empty frame." + if frame_arr.ndim == 2: + color = frame_arr + else: + assert frame_arr.shape[-1] >= 3, f"Expected at least 3 channels, got shape {frame_arr.shape}." + color = frame_arr[..., :3] + finite = np.where(np.isfinite(color), color, 0) + assert np.count_nonzero(finite) > 0, "Viewer frame appears fully black." + + +def _step_until_non_black_camera(env, actions: torch.Tensor, *, max_steps: int = _MAX_NON_BLACK_STEPS) -> None: + """Step env until camera frame is non-black, bounded by max_steps.""" + last_rgb = None + for _ in range(max_steps): + env.step(action=actions) + rgb = env._tiled_camera.data.output.get("rgb") + if rgb is None: + rgb = env._tiled_camera.data.output[env.cfg.tiled_camera.data_types[0]] + last_rgb = rgb + try: + _assert_non_black_tensor(rgb) + return + except AssertionError: + continue + # Preserve existing assertion semantics with a final explicit check. + _assert_non_black_tensor(last_rgb) + + +def _make_cartpole_camera_env(visualizer_kind: str, backend_kind: str) -> CartpoleCameraEnv: + """Create cartpole camera env configured with selected visualizer and physics backend.""" + env_cfg_root = CartpoleCameraPresetsEnvCfg() + env_cfg = getattr(env_cfg_root, "default", None) + if env_cfg is None: + env_cfg = getattr(type(env_cfg_root), "default", None) + if env_cfg is None: + raise RuntimeError( + "CartpoleCameraPresetsEnvCfg does not expose a 'default' preset config. " + f"Available attributes: {sorted(vars(env_cfg_root).keys())}" + ) + env_cfg = copy.deepcopy(env_cfg) + env_cfg.scene.num_envs = 1 + # Avoid hard dependency on replicator graph initialization in this smoke test; + # deterministic seeding is not required for black-frame detection coverage. + env_cfg.seed = None + env_cfg.sim.physics, _ = _get_physics_cfg(backend_kind) + visualizer_cfg, _ = _get_visualizer_cfg(visualizer_kind) + env_cfg.sim.visualizer_cfgs = visualizer_cfg + return CartpoleCameraEnv(env_cfg) + + def _resolve_case(visualizer_kind: str, backend_kind: str): """Resolve (env_cfg, expected_visualizer_cls, expected_backend_substring) for one smoke test. @@ -224,5 +295,57 @@ def test_visualizer_backend_smoke(visualizer_kind: str, backend_kind: str, caplo _run_smoke_test(cfg, expected_viz_cls, expected_backend, caplog) +@pytest.mark.isaacsim_ci +@pytest.mark.parametrize("visualizer_kind", ["kit", "newton", "rerun", "viser"]) +@pytest.mark.parametrize("backend_kind", ["physx", "newton"]) +def test_cartpole_visualizer_non_black_camera_frame(visualizer_kind: str, backend_kind: str): + """Cartpole tiled-camera output should not be black when visualizers are enabled.""" + env = None + try: + sim_utils.create_new_stage() + env = _make_cartpole_camera_env(visualizer_kind=visualizer_kind, backend_kind=backend_kind) + env.sim._app_control_on_stop_handle = None # type: ignore[attr-defined] + env.reset() + actions = torch.zeros((env.num_envs, env.action_space.shape[-1]), device=env.device) + _step_until_non_black_camera(env, actions, max_steps=_MAX_NON_BLACK_STEPS) + finally: + if env is not None: + env.close() + else: + SimulationContext.clear_instance() + + +@pytest.mark.isaacsim_ci +@pytest.mark.parametrize("backend_kind", ["physx", "newton"]) +def test_newton_visualizer_non_black_viewer_frame(backend_kind: str): + """Newton visualizer should produce at least one non-black viewer frame for Cartpole.""" + env = None + try: + sim_utils.create_new_stage() + env = _make_cartpole_camera_env(visualizer_kind="newton", backend_kind=backend_kind) + env.sim._app_control_on_stop_handle = None # type: ignore[attr-defined] + env.reset() + actions = torch.zeros((env.num_envs, env.action_space.shape[-1]), device=env.device) + for _ in range(_MAX_NON_BLACK_STEPS): + env.step(action=actions) + + newton_visualizers = [viz for viz in env.sim.visualizers if isinstance(viz, NewtonVisualizer)] + assert newton_visualizers, "Expected an initialized Newton visualizer." + viewer = getattr(newton_visualizers[0], "_viewer", None) + assert viewer is not None, "Newton viewer was not created." + + get_frame = getattr(viewer, "get_frame", None) + if not callable(get_frame): + pytest.skip("ViewerGL.get_frame is not available in this Newton version.") + + frame = get_frame() + _assert_non_black_frame_array(frame) + finally: + if env is not None: + env.close() + else: + SimulationContext.clear_instance() + + if __name__ == "__main__": pytest.main([__file__, "-v", "--maxfail=1"]) From 6b4d4473973a4ca5b1103534ca7d354b9e1c35cf Mon Sep 17 00:00:00 2001 From: Matthew Trepte Date: Tue, 24 Mar 2026 20:15:53 +0000 Subject: [PATCH 03/11] fix kit visualizer test --- .../test/test_visualizer_smoke_logs.py | 91 +++++++++++++++++-- 1 file changed, 81 insertions(+), 10 deletions(-) diff --git a/source/isaaclab_visualizers/test/test_visualizer_smoke_logs.py b/source/isaaclab_visualizers/test/test_visualizer_smoke_logs.py index 8ac9e1f06ea1..db16d039bc4a 100644 --- a/source/isaaclab_visualizers/test/test_visualizer_smoke_logs.py +++ b/source/isaaclab_visualizers/test/test_visualizer_smoke_logs.py @@ -10,9 +10,10 @@ # launch Kit app simulation_app = AppLauncher(headless=True, enable_cameras=True).app +import contextlib +import copy import logging import socket -import copy import numpy as np import pytest @@ -27,9 +28,9 @@ from isaaclab.scene import InteractiveSceneCfg from isaaclab.sim import SimulationCfg, SimulationContext from isaaclab.utils import configclass + from isaaclab_tasks.direct.cartpole.cartpole_camera_env import CartpoleCameraEnv from isaaclab_tasks.direct.cartpole.cartpole_camera_presets_env_cfg import CartpoleCameraPresetsEnvCfg - from isaaclab_tasks.manager_based.classic.cartpole.cartpole_env_cfg import ( CartpolePhysicsCfg, CartpoleSceneCfg, @@ -200,6 +201,55 @@ def _step_until_non_black_camera(env, actions: torch.Tensor, *, max_steps: int = _assert_non_black_tensor(last_rgb) +def _build_rgb_annotator_for_camera(camera_path: str, *, resolution: tuple[int, int] = (320, 240)): + """Create CPU RGB annotator attached to a camera render product.""" + import omni.replicator.core as rep + + render_product = rep.create.render_product(camera_path, resolution=resolution) + annotator = rep.AnnotatorRegistry.get_annotator("rgb", device="cpu") + annotator.attach([render_product]) + return annotator, render_product + + +def _annotator_rgb_to_numpy(rgb_data) -> np.ndarray: + """Convert replicator annotator output to HxWx3 uint8 numpy array.""" + rgb_array = np.frombuffer(rgb_data, dtype=np.uint8).reshape(*rgb_data.shape) + if rgb_array.size == 0: + return np.zeros((1, 1, 3), dtype=np.uint8) + return rgb_array[:, :, :3] + + +def _step_until_non_black_kit_viewport( + env, kit_visualizer: KitVisualizer, *, max_steps: int = _MAX_NON_BLACK_STEPS +) -> None: + """Step env until Kit viewport camera render product is non-black, bounded by max_steps.""" + camera_path = getattr(kit_visualizer, "_controlled_camera_path", None) + if not camera_path: + pytest.skip("Kit visualizer does not expose a controlled viewport camera path.") + + annotator = None + render_product = None + try: + annotator, render_product = _build_rgb_annotator_for_camera(camera_path) + actions = torch.zeros((env.num_envs, env.action_space.shape[-1]), device=env.device) + last_frame = None + for _ in range(max_steps): + env.step(action=actions) + rgb_data = annotator.get_data() + frame = _annotator_rgb_to_numpy(rgb_data) + last_frame = frame + try: + _assert_non_black_frame_array(frame) + return + except AssertionError: + continue + _assert_non_black_frame_array(last_frame) + finally: + if annotator is not None and render_product is not None: + with contextlib.suppress(Exception): + annotator.detach([render_product]) + + def _make_cartpole_camera_env(visualizer_kind: str, backend_kind: str) -> CartpoleCameraEnv: """Create cartpole camera env configured with selected visualizer and physics backend.""" env_cfg_root = CartpoleCameraPresetsEnvCfg() @@ -222,6 +272,25 @@ def _make_cartpole_camera_env(visualizer_kind: str, backend_kind: str) -> Cartpo return CartpoleCameraEnv(env_cfg) +def _make_cartpole_camera_env_with_visualizers(visualizer_kinds: list[str], backend_kind: str) -> CartpoleCameraEnv: + """Create cartpole camera env with multiple visualizers active at once.""" + env_cfg_root = CartpoleCameraPresetsEnvCfg() + env_cfg = getattr(env_cfg_root, "default", None) + if env_cfg is None: + env_cfg = getattr(type(env_cfg_root), "default", None) + if env_cfg is None: + raise RuntimeError( + "CartpoleCameraPresetsEnvCfg does not expose a 'default' preset config. " + f"Available attributes: {sorted(vars(env_cfg_root).keys())}" + ) + env_cfg = copy.deepcopy(env_cfg) + env_cfg.scene.num_envs = 1 + env_cfg.seed = None + env_cfg.sim.physics, _ = _get_physics_cfg(backend_kind) + env_cfg.sim.visualizer_cfgs = [_get_visualizer_cfg(kind)[0] for kind in visualizer_kinds] + return CartpoleCameraEnv(env_cfg) + + def _resolve_case(visualizer_kind: str, backend_kind: str): """Resolve (env_cfg, expected_visualizer_cls, expected_backend_substring) for one smoke test. @@ -296,18 +365,20 @@ def test_visualizer_backend_smoke(visualizer_kind: str, backend_kind: str, caplo @pytest.mark.isaacsim_ci -@pytest.mark.parametrize("visualizer_kind", ["kit", "newton", "rerun", "viser"]) -@pytest.mark.parametrize("backend_kind", ["physx", "newton"]) -def test_cartpole_visualizer_non_black_camera_frame(visualizer_kind: str, backend_kind: str): - """Cartpole tiled-camera output should not be black when visualizers are enabled.""" +@pytest.mark.parametrize("backend_kind", ["physx"]) +def test_kit_visualizer_non_black_viewport_frame(backend_kind: str): + """Kit visualizer viewport camera output should not be black.""" env = None try: sim_utils.create_new_stage() - env = _make_cartpole_camera_env(visualizer_kind=visualizer_kind, backend_kind=backend_kind) + env = _make_cartpole_camera_env_with_visualizers( + visualizer_kinds=["kit", "newton", "rerun", "viser"], backend_kind=backend_kind + ) env.sim._app_control_on_stop_handle = None # type: ignore[attr-defined] env.reset() - actions = torch.zeros((env.num_envs, env.action_space.shape[-1]), device=env.device) - _step_until_non_black_camera(env, actions, max_steps=_MAX_NON_BLACK_STEPS) + kit_visualizers = [viz for viz in env.sim.visualizers if isinstance(viz, KitVisualizer)] + assert kit_visualizers, "Expected an initialized Kit visualizer." + _step_until_non_black_kit_viewport(env, kit_visualizers[0], max_steps=_MAX_NON_BLACK_STEPS) finally: if env is not None: env.close() @@ -316,7 +387,7 @@ def test_cartpole_visualizer_non_black_camera_frame(visualizer_kind: str, backen @pytest.mark.isaacsim_ci -@pytest.mark.parametrize("backend_kind", ["physx", "newton"]) +@pytest.mark.parametrize("backend_kind", ["physx"]) def test_newton_visualizer_non_black_viewer_frame(backend_kind: str): """Newton visualizer should produce at least one non-black viewer frame for Cartpole.""" env = None From 8a93f84febc631c828132d130c7c55d8cb849144 Mon Sep 17 00:00:00 2001 From: Matthew Trepte Date: Tue, 24 Mar 2026 20:46:28 +0000 Subject: [PATCH 04/11] readd physx flag --- .../isaaclab_visualizers/kit/kit_visualizer.py | 11 ++++++++++- 1 file changed, 10 insertions(+), 1 deletion(-) diff --git a/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualizer.py b/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualizer.py index 47ea1e75c883..d1def2f06bc7 100644 --- a/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualizer.py +++ b/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualizer.py @@ -103,12 +103,21 @@ def step(self, dt: float) -> None: self._sim_time += dt self._step_counter += 1 try: + import carb.settings import omni.kit.app app = omni.kit.app.get_app() if app is not None and app.is_running(): # Pump Kit/UI events only; SimulationContext owns physics stepping. - app.update() + settings = carb.settings.get_settings() + play_simulations_path = "/app/player/playSimulations" + previous_play_simulations = None if settings is None else settings.get(play_simulations_path) + should_restore = bool(previous_play_simulations) + if should_restore: + settings.set_bool(play_simulations_path, False) + app.update() + if should_restore: + settings.set_bool(play_simulations_path, True) except (ImportError, AttributeError) as exc: logger.debug("[KitVisualizer] App update skipped: %s", exc) From 77152f2fe4c28c3a681efd4068d1921345bf3515 Mon Sep 17 00:00:00 2001 From: Matthew Trepte Date: Tue, 24 Mar 2026 20:50:28 +0000 Subject: [PATCH 05/11] clean tests --- .../test/test_visualizer_smoke_logs.py | 23 +------------------ 1 file changed, 1 insertion(+), 22 deletions(-) diff --git a/source/isaaclab_visualizers/test/test_visualizer_smoke_logs.py b/source/isaaclab_visualizers/test/test_visualizer_smoke_logs.py index db16d039bc4a..4df4cd9835cc 100644 --- a/source/isaaclab_visualizers/test/test_visualizer_smoke_logs.py +++ b/source/isaaclab_visualizers/test/test_visualizer_smoke_logs.py @@ -272,25 +272,6 @@ def _make_cartpole_camera_env(visualizer_kind: str, backend_kind: str) -> Cartpo return CartpoleCameraEnv(env_cfg) -def _make_cartpole_camera_env_with_visualizers(visualizer_kinds: list[str], backend_kind: str) -> CartpoleCameraEnv: - """Create cartpole camera env with multiple visualizers active at once.""" - env_cfg_root = CartpoleCameraPresetsEnvCfg() - env_cfg = getattr(env_cfg_root, "default", None) - if env_cfg is None: - env_cfg = getattr(type(env_cfg_root), "default", None) - if env_cfg is None: - raise RuntimeError( - "CartpoleCameraPresetsEnvCfg does not expose a 'default' preset config. " - f"Available attributes: {sorted(vars(env_cfg_root).keys())}" - ) - env_cfg = copy.deepcopy(env_cfg) - env_cfg.scene.num_envs = 1 - env_cfg.seed = None - env_cfg.sim.physics, _ = _get_physics_cfg(backend_kind) - env_cfg.sim.visualizer_cfgs = [_get_visualizer_cfg(kind)[0] for kind in visualizer_kinds] - return CartpoleCameraEnv(env_cfg) - - def _resolve_case(visualizer_kind: str, backend_kind: str): """Resolve (env_cfg, expected_visualizer_cls, expected_backend_substring) for one smoke test. @@ -371,9 +352,7 @@ def test_kit_visualizer_non_black_viewport_frame(backend_kind: str): env = None try: sim_utils.create_new_stage() - env = _make_cartpole_camera_env_with_visualizers( - visualizer_kinds=["kit", "newton", "rerun", "viser"], backend_kind=backend_kind - ) + env = _make_cartpole_camera_env(visualizer_kind="kit", backend_kind=backend_kind) env.sim._app_control_on_stop_handle = None # type: ignore[attr-defined] env.reset() kit_visualizers = [viz for viz in env.sim.visualizers if isinstance(viz, KitVisualizer)] From 4a42c18b9cabb7cc866e4e972fe77fdb167dee27 Mon Sep 17 00:00:00 2001 From: Matthew Trepte Date: Tue, 24 Mar 2026 20:56:12 +0000 Subject: [PATCH 06/11] physics backends --- .../isaaclab_visualizers/test/test_visualizer_smoke_logs.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/source/isaaclab_visualizers/test/test_visualizer_smoke_logs.py b/source/isaaclab_visualizers/test/test_visualizer_smoke_logs.py index 4df4cd9835cc..83cfc36b7194 100644 --- a/source/isaaclab_visualizers/test/test_visualizer_smoke_logs.py +++ b/source/isaaclab_visualizers/test/test_visualizer_smoke_logs.py @@ -346,7 +346,7 @@ def test_visualizer_backend_smoke(visualizer_kind: str, backend_kind: str, caplo @pytest.mark.isaacsim_ci -@pytest.mark.parametrize("backend_kind", ["physx"]) +@pytest.mark.parametrize("backend_kind", ["physx", "newton"]) def test_kit_visualizer_non_black_viewport_frame(backend_kind: str): """Kit visualizer viewport camera output should not be black.""" env = None @@ -366,7 +366,7 @@ def test_kit_visualizer_non_black_viewport_frame(backend_kind: str): @pytest.mark.isaacsim_ci -@pytest.mark.parametrize("backend_kind", ["physx"]) +@pytest.mark.parametrize("backend_kind", ["physx", "newton"]) def test_newton_visualizer_non_black_viewer_frame(backend_kind: str): """Newton visualizer should produce at least one non-black viewer frame for Cartpole.""" env = None From 5bb5e6b6c692f3868509681e66a5e16c647d232d Mon Sep 17 00:00:00 2001 From: Matthew Trepte Date: Wed, 25 Mar 2026 22:29:19 +0000 Subject: [PATCH 07/11] wip --- source/isaaclab/isaaclab/envs/common.py | 7 +- .../isaaclab/isaaclab/envs/direct_marl_env.py | 27 ++- .../isaaclab/isaaclab/envs/direct_rl_env.py | 27 ++- .../isaaclab/envs/manager_based_env.py | 2 +- .../isaaclab/envs/manager_based_rl_env.py | 30 ++- .../envs/mdp/commands/velocity_command.py | 186 ++++++++++++++++++ .../isaaclab/envs/ui/base_env_window.py | 4 +- .../envs/ui/viewport_camera_controller.py | 6 +- .../isaaclab/sim/simulation_context.py | 33 ++++ .../test/envs/test_color_randomization.py | 4 +- .../test/envs/test_texture_randomization.py | 4 +- .../isaaclab_physx/physics/physx_manager.py | 25 ++- .../cartpole/cartpole_camera_env_cfg.py | 8 +- .../classic/cartpole/cartpole_env_cfg.py | 2 +- .../manipulation/cabinet/cabinet_env_cfg.py | 4 +- .../config/openarm/cabinet_openarm_env_cfg.py | 4 +- .../gear_assembly/gear_assembly_env_cfg.py | 2 +- .../deploy/reach/reach_env_cfg.py | 2 +- .../manipulation/inhand/inhand_env_cfg.py | 2 +- .../agibot/place_toy2box_rmp_rel_env_cfg.py | 4 +- .../bimanual/reach_openarm_bi_env_cfg.py | 2 +- .../unimanual/reach_openarm_uni_env_cfg.py | 2 +- .../manipulation/reach/reach_env_cfg.py | 2 +- .../kit/kit_visualizer.py | 47 ++++- 24 files changed, 387 insertions(+), 49 deletions(-) diff --git a/source/isaaclab/isaaclab/envs/common.py b/source/isaaclab/isaaclab/envs/common.py index f913005d1dbb..f8bc39d4f6b2 100644 --- a/source/isaaclab/isaaclab/envs/common.py +++ b/source/isaaclab/isaaclab/envs/common.py @@ -21,10 +21,10 @@ class ViewerCfg: """Configuration of the scene viewport camera.""" - eye: tuple[float, float, float] = (7.5, 7.5, 7.5) + position: tuple[float, float, float] = (7.5, 17.5, 17.5) """Initial camera position (in m). Default is (7.5, 7.5, 7.5).""" - lookat: tuple[float, float, float] = (0.0, 0.0, 0.0) + target_position: tuple[float, float, float] = (0.0, 0.0, 5.0) """Initial camera target position (in m). Default is (0.0, 0.0, 0.0).""" cam_prim_path: str = "/OmniverseKit_Persp" @@ -38,7 +38,7 @@ class ViewerCfg: """ origin_type: Literal["world", "env", "asset_root", "asset_body"] = "world" - """The frame in which the camera position (eye) and target (lookat) are defined in. Default is "world". + """The frame in which the camera position and target are defined in. Default is "world". Available options are: @@ -67,7 +67,6 @@ class ViewerCfg: This quantity is only effective if :attr:`origin` is set to "asset_body". """ - ## # Types. ## diff --git a/source/isaaclab/isaaclab/envs/direct_marl_env.py b/source/isaaclab/isaaclab/envs/direct_marl_env.py index eb0a359e4f5b..4e0718be9e1a 100644 --- a/source/isaaclab/isaaclab/envs/direct_marl_env.py +++ b/source/isaaclab/isaaclab/envs/direct_marl_env.py @@ -152,7 +152,7 @@ def _init_sim(self, render_mode: str | None = None, **kwargs): # non-rendering modes. # Initialize when GUI is available OR when visualizers are active (headless rendering) # Visualizers support camera updates via sim.set_camera_view() which forwards to all active visualizers - has_visualizers = bool(self.sim.get_setting("/isaaclab/visualizer")) + has_visualizers = bool(self.sim.get_setting("/isaaclab/visualizer/types")) if self.sim.has_gui or has_visualizers: self.viewport_camera_controller = ViewportCameraController(self, self.cfg.viewer) else: @@ -531,10 +531,11 @@ def render(self, recompute: bool = False) -> np.ndarray | None: if not hasattr(self, "_rgb_annotator"): import omni.replicator.core as rep + camera_prim_path = self.cfg.viewer.cam_prim_path + self._set_rgb_array_camera_view(camera_prim_path) + # create render product - self._render_product = rep.create.render_product( - self.cfg.viewer.cam_prim_path, self.cfg.viewer.resolution - ) + self._render_product = rep.create.render_product(camera_prim_path, self.cfg.viewer.resolution) # create rgb annotator -- used to read data from the render product self._rgb_annotator = rep.AnnotatorRegistry.get_annotator("rgb", device="cpu") self._rgb_annotator.attach([self._render_product]) @@ -553,6 +554,24 @@ def render(self, recompute: bool = False) -> np.ndarray | None: f"Render mode '{self.render_mode}' is not supported. Please use: {self.metadata['render_modes']}." ) + def _set_rgb_array_camera_view(self, camera_prim_path: str) -> None: + """Set perspective camera pose for rgb-array capture (headless-safe).""" + try: + import isaacsim.core.utils.viewports as isaacsim_viewports + + viewer_origin = torch.zeros(3, dtype=torch.float32) + if self.cfg.viewer.origin_type == "env" and self.num_envs > 0: + env_index = max(0, min(self.cfg.viewer.env_index, self.num_envs - 1)) + viewer_origin = self.scene.env_origins[env_index].detach().cpu().float() + else: + viewer_origin = viewer_origin.cpu() + + cam_eye = (viewer_origin + torch.tensor(self.cfg.viewer.position, dtype=torch.float32)).tolist() + cam_target = (viewer_origin + torch.tensor(self.cfg.viewer.target_position, dtype=torch.float32)).tolist() + isaacsim_viewports.set_camera_view(eye=cam_eye, target=cam_target, camera_prim_path=camera_prim_path) + except Exception as exc: + logger.debug("Failed to set rgb-array camera view for '%s': %s", camera_prim_path, exc) + def close(self): """Cleanup for the environment.""" if not self._is_closed: diff --git a/source/isaaclab/isaaclab/envs/direct_rl_env.py b/source/isaaclab/isaaclab/envs/direct_rl_env.py index b362ac72bc21..5c1e24ae8a45 100644 --- a/source/isaaclab/isaaclab/envs/direct_rl_env.py +++ b/source/isaaclab/isaaclab/envs/direct_rl_env.py @@ -157,7 +157,7 @@ def _init_sim(self, render_mode: str | None = None, **kwargs): # non-rendering modes. # Initialize when GUI is available OR when visualizers are active (headless rendering) # Visualizers support camera updates via sim.set_camera_view() which forwards to all active visualizers - has_visualizers = bool(self.sim.get_setting("/isaaclab/visualizer")) + has_visualizers = bool(self.sim.get_setting("/isaaclab/visualizer/types")) if self.sim.has_gui or has_visualizers: self.viewport_camera_controller = ViewportCameraController(self, self.cfg.viewer) else: @@ -499,10 +499,11 @@ def render(self, recompute: bool = False) -> np.ndarray | None: if not hasattr(self, "_rgb_annotator"): import omni.replicator.core as rep + camera_prim_path = self.cfg.viewer.cam_prim_path + self._set_rgb_array_camera_view(camera_prim_path) + # create render product - self._render_product = rep.create.render_product( - self.cfg.viewer.cam_prim_path, self.cfg.viewer.resolution - ) + self._render_product = rep.create.render_product(camera_prim_path, self.cfg.viewer.resolution) # create rgb annotator -- used to read data from the render product self._rgb_annotator = rep.AnnotatorRegistry.get_annotator("rgb", device="cpu") self._rgb_annotator.attach([self._render_product]) @@ -521,6 +522,24 @@ def render(self, recompute: bool = False) -> np.ndarray | None: f"Render mode '{self.render_mode}' is not supported. Please use: {self.metadata['render_modes']}." ) + def _set_rgb_array_camera_view(self, camera_prim_path: str) -> None: + """Set perspective camera pose for rgb-array capture (headless-safe).""" + try: + import isaacsim.core.utils.viewports as isaacsim_viewports + + viewer_origin = torch.zeros(3, dtype=torch.float32) + if self.cfg.viewer.origin_type == "env" and self.num_envs > 0: + env_index = max(0, min(self.cfg.viewer.env_index, self.num_envs - 1)) + viewer_origin = self.scene.env_origins[env_index].detach().cpu().float() + else: + viewer_origin = viewer_origin.cpu() + + cam_eye = (viewer_origin + torch.tensor(self.cfg.viewer.position, dtype=torch.float32)).tolist() + cam_target = (viewer_origin + torch.tensor(self.cfg.viewer.target_position, dtype=torch.float32)).tolist() + isaacsim_viewports.set_camera_view(eye=cam_eye, target=cam_target, camera_prim_path=camera_prim_path) + except Exception as exc: + logger.debug("Failed to set rgb-array camera view for '%s': %s", camera_prim_path, exc) + def close(self): """Cleanup for the environment.""" if not self._is_closed: diff --git a/source/isaaclab/isaaclab/envs/manager_based_env.py b/source/isaaclab/isaaclab/envs/manager_based_env.py index 996e88216e17..3f003bfeb184 100644 --- a/source/isaaclab/isaaclab/envs/manager_based_env.py +++ b/source/isaaclab/isaaclab/envs/manager_based_env.py @@ -167,7 +167,7 @@ def _init_sim(self): # non-rendering modes. # Initialize when GUI is available OR when visualizers are active (headless rendering) # Visualizers support camera updates via sim.set_camera_view() which forwards to all active visualizers - has_visualizers = bool(self.sim.get_setting("/isaaclab/visualizer")) + has_visualizers = bool(self.sim.get_setting("/isaaclab/visualizer/types")) if self.sim.has_gui or has_visualizers: self.viewport_camera_controller = ViewportCameraController(self, self.cfg.viewer) else: diff --git a/source/isaaclab/isaaclab/envs/manager_based_rl_env.py b/source/isaaclab/isaaclab/envs/manager_based_rl_env.py index d08b7e3be3a7..d3f9723b0838 100644 --- a/source/isaaclab/isaaclab/envs/manager_based_rl_env.py +++ b/source/isaaclab/isaaclab/envs/manager_based_rl_env.py @@ -6,6 +6,7 @@ # needed to import for allowing type-hinting: np.ndarray | None from __future__ import annotations +import logging import math from collections.abc import Sequence from typing import Any, ClassVar @@ -21,6 +22,8 @@ from .manager_based_env import ManagerBasedEnv from .manager_based_rl_env_cfg import ManagerBasedRLEnvCfg +logger = logging.getLogger(__name__) + class ManagerBasedRLEnv(ManagerBasedEnv, gym.Env): """The superclass for the manager-based workflow reinforcement learning-based environments. @@ -272,7 +275,7 @@ def render(self, recompute: bool = False) -> np.ndarray | None: elif self.render_mode == "rgb_array": # check that if any render could have happened # Check for GUI, offscreen rendering, or visualizers - has_visualizers = bool(self.sim.get_setting("/isaaclab/visualizer")) + has_visualizers = bool(self.sim.get_setting("/isaaclab/visualizer/types")) if not (self.sim.has_gui or self.sim.has_offscreen_render or has_visualizers): raise RuntimeError( f"Cannot render '{self.render_mode}' - no GUI and offscreen rendering not enabled." @@ -282,10 +285,11 @@ def render(self, recompute: bool = False) -> np.ndarray | None: if not hasattr(self, "_rgb_annotator"): import omni.replicator.core as rep + camera_prim_path = self.cfg.viewer.cam_prim_path + self._set_rgb_array_camera_view(camera_prim_path) + # create render product - self._render_product = rep.create.render_product( - self.cfg.viewer.cam_prim_path, self.cfg.viewer.resolution - ) + self._render_product = rep.create.render_product(camera_prim_path, self.cfg.viewer.resolution) # create rgb annotator -- used to read data from the render product self._rgb_annotator = rep.AnnotatorRegistry.get_annotator("rgb", device="cpu") self._rgb_annotator.attach([self._render_product]) @@ -304,6 +308,24 @@ def render(self, recompute: bool = False) -> np.ndarray | None: f"Render mode '{self.render_mode}' is not supported. Please use: {self.metadata['render_modes']}." ) + def _set_rgb_array_camera_view(self, camera_prim_path: str) -> None: + """Set perspective camera pose for rgb-array capture (headless-safe).""" + try: + import isaacsim.core.utils.viewports as isaacsim_viewports + + viewer_origin = torch.zeros(3, dtype=torch.float32) + if self.cfg.viewer.origin_type == "env" and self.num_envs > 0: + env_index = max(0, min(self.cfg.viewer.env_index, self.num_envs - 1)) + viewer_origin = self.scene.env_origins[env_index].detach().cpu().float() + else: + viewer_origin = viewer_origin.cpu() + + cam_eye = (viewer_origin + torch.tensor(self.cfg.viewer.position, dtype=torch.float32)).tolist() + cam_target = (viewer_origin + torch.tensor(self.cfg.viewer.target_position, dtype=torch.float32)).tolist() + isaacsim_viewports.set_camera_view(eye=cam_eye, target=cam_target, camera_prim_path=camera_prim_path) + except Exception as exc: + logger.debug("Failed to set rgb-array camera view for '%s': %s", camera_prim_path, exc) + def close(self): if not self._is_closed: # destructor is order-sensitive diff --git a/source/isaaclab/isaaclab/envs/mdp/commands/velocity_command.py b/source/isaaclab/isaaclab/envs/mdp/commands/velocity_command.py index eadc89af3af9..4019917ee97d 100644 --- a/source/isaaclab/isaaclab/envs/mdp/commands/velocity_command.py +++ b/source/isaaclab/isaaclab/envs/mdp/commands/velocity_command.py @@ -8,6 +8,8 @@ from __future__ import annotations import logging +import os +import re from collections.abc import Sequence from typing import TYPE_CHECKING @@ -26,6 +28,7 @@ # import logger logger = logging.getLogger(__name__) +_VIS_DEBUG_ENABLED = os.getenv("ISAACLAB_VIS_DEBUG", "0").lower() in {"1", "true", "yes", "on"} class UniformVelocityCommand(CommandTerm): @@ -84,6 +87,9 @@ def __init__(self, cfg: UniformVelocityCommandCfg, env: ManagerBasedEnv): self.heading_target = torch.zeros(self.num_envs, device=self.device) self.is_heading_env = torch.zeros(self.num_envs, dtype=torch.bool, device=self.device) self.is_standing_env = torch.zeros_like(self.is_heading_env) + self._debug_vis_callback_count = 0 + self._debug_env0_probe_body_path: str | None = None + self._debug_env0_probe_status: str = "uninitialized" # -- metrics self.metrics["error_vel_xy"] = torch.zeros(self.num_envs, device=self.device) self.metrics["error_vel_yaw"] = torch.zeros(self.num_envs, device=self.device) @@ -201,6 +207,83 @@ def _debug_vis_callback(self, event): # display markers self.goal_vel_visualizer.visualize(base_pos_w, vel_des_arrow_quat, vel_des_arrow_scale) self.current_vel_visualizer.visualize(base_pos_w, vel_arrow_quat, vel_arrow_scale) + self._debug_vis_callback_count += 1 + if _VIS_DEBUG_ENABLED and ( + self._debug_vis_callback_count <= 3 or self._debug_vis_callback_count % 120 == 0 + ): + mean_cmd = float(torch.linalg.norm(self.command[:, :2], dim=-1).mean().item()) + mean_vel = float(torch.linalg.norm(wp.to_torch(self.robot.data.root_lin_vel_b)[:, :2], dim=-1).mean().item()) + tensor_root_pos = wp.to_torch(self.robot.data.root_pos_w)[0].detach().cpu() + fabric_root_pos = self._get_env0_fabric_probe_position() + root_view_pos = self._get_env0_root_view_position() + robot_root = self._resolve_env0_robot_root_path() + fabric_base_pos = self._get_fabric_position_for_path(f"{robot_root}/base") if robot_root else None + fabric_trunk_pos = self._get_fabric_position_for_path(f"{robot_root}/trunk") if robot_root else None + if fabric_root_pos is not None: + fabric_root_pos_t = torch.tensor(fabric_root_pos, dtype=tensor_root_pos.dtype) + delta = torch.linalg.norm(tensor_root_pos - fabric_root_pos_t).item() + root_view_delta = None + if root_view_pos is not None: + root_view_pos_t = torch.tensor(root_view_pos, dtype=tensor_root_pos.dtype) + root_view_delta = torch.linalg.norm(tensor_root_pos - root_view_pos_t).item() + logger.warning( + "[VIS-DEBUG][UniformVelocityCommand._debug_vis_callback] count=%d mean_cmd_xy=%.4f " + "mean_vel_xy=%.4f env0_tensor_root=(%.3f, %.3f, %.3f) env0_fabric_root=(%.3f, %.3f, %.3f) " + "tensor_fabric_delta=%.5f root_view_delta=%s fabric_base=%s fabric_trunk=%s " + "probe_path=%s probe_status=%s", + self._debug_vis_callback_count, + mean_cmd, + mean_vel, + float(tensor_root_pos[0]), + float(tensor_root_pos[1]), + float(tensor_root_pos[2]), + float(fabric_root_pos_t[0]), + float(fabric_root_pos_t[1]), + float(fabric_root_pos_t[2]), + float(delta), + f"{root_view_delta:.5f}" if root_view_delta is not None else "", + ( + f"({fabric_base_pos[0]:.3f}, {fabric_base_pos[1]:.3f}, {fabric_base_pos[2]:.3f})" + if fabric_base_pos is not None + else "" + ), + ( + f"({fabric_trunk_pos[0]:.3f}, {fabric_trunk_pos[1]:.3f}, {fabric_trunk_pos[2]:.3f})" + if fabric_trunk_pos is not None + else "" + ), + self._debug_env0_probe_body_path or "", + self._debug_env0_probe_status, + ) + else: + logger.warning( + "[VIS-DEBUG][UniformVelocityCommand._debug_vis_callback] count=%d mean_cmd_xy=%.4f " + "mean_vel_xy=%.4f env0_tensor_root=(%.3f, %.3f, %.3f) env0_fabric_root= " + "root_view=%s fabric_base=%s fabric_trunk=%s probe_path=%s probe_status=%s", + self._debug_vis_callback_count, + mean_cmd, + mean_vel, + float(tensor_root_pos[0]), + float(tensor_root_pos[1]), + float(tensor_root_pos[2]), + ( + f"({root_view_pos[0]:.3f}, {root_view_pos[1]:.3f}, {root_view_pos[2]:.3f})" + if root_view_pos is not None + else "" + ), + ( + f"({fabric_base_pos[0]:.3f}, {fabric_base_pos[1]:.3f}, {fabric_base_pos[2]:.3f})" + if fabric_base_pos is not None + else "" + ), + ( + f"({fabric_trunk_pos[0]:.3f}, {fabric_trunk_pos[1]:.3f}, {fabric_trunk_pos[2]:.3f})" + if fabric_trunk_pos is not None + else "" + ), + self._debug_env0_probe_body_path or "", + self._debug_env0_probe_status, + ) """ Internal helpers. @@ -223,6 +306,109 @@ def _resolve_xy_velocity_to_arrow(self, xy_velocity: torch.Tensor) -> tuple[torc return arrow_scale, arrow_quat + def _resolve_env0_robot_root_path(self) -> str | None: + """Best-effort resolve env_0 robot root path from articulation cfg prim path.""" + prim_path = getattr(self.robot.cfg, "prim_path", None) + if not isinstance(prim_path, str) or not prim_path: + return None + path = prim_path + if "{ENV_REGEX_NS}" in path: + path = path.replace("{ENV_REGEX_NS}", "/World/envs/env_0") + path = path.replace("env_.*", "env_0") + path = re.sub(r"\.\*$", "0", path) + return path + + def _resolve_env0_fabric_probe_body_path(self) -> str | None: + """Resolve a rigid-body prim path for env_0 suitable for Fabric world-matrix probing.""" + if self._debug_env0_probe_body_path is not None: + return self._debug_env0_probe_body_path + try: + from pxr import UsdPhysics + + stage = self._env.sim.stage + if stage is None: + self._debug_env0_probe_status = "no_stage" + return None + robot_root = self._resolve_env0_robot_root_path() + if not robot_root: + self._debug_env0_probe_status = "no_robot_root_path" + return None + root_prim = stage.GetPrimAtPath(robot_root) + if not root_prim.IsValid(): + self._debug_env0_probe_status = f"invalid_robot_root:{robot_root}" + return None + + # First try common body names directly under Robot to avoid brittle traversal assumptions. + fallback_candidates = [ + f"{robot_root}/base", + f"{robot_root}/base_link", + f"{robot_root}/trunk", + f"{robot_root}/pelvis", + ] + for candidate in fallback_candidates: + prim = stage.GetPrimAtPath(candidate) + if prim.IsValid() and prim.HasAPI(UsdPhysics.RigidBodyAPI): + self._debug_env0_probe_body_path = candidate + self._debug_env0_probe_status = "resolved_fallback_candidate" + return self._debug_env0_probe_body_path + + preferred_names = {"base", "base_link", "trunk", "pelvis"} + for prim in root_prim.Traverse(): + if not prim.IsValid() or not prim.HasAPI(UsdPhysics.RigidBodyAPI): + continue + if prim.GetName() in preferred_names: + self._debug_env0_probe_body_path = prim.GetPath().pathString + self._debug_env0_probe_status = "resolved_traverse_preferred" + return self._debug_env0_probe_body_path + for prim in root_prim.Traverse(): + if prim.IsValid() and prim.HasAPI(UsdPhysics.RigidBodyAPI): + self._debug_env0_probe_body_path = prim.GetPath().pathString + self._debug_env0_probe_status = "resolved_traverse_first_rigidbody" + return self._debug_env0_probe_body_path + self._debug_env0_probe_status = "no_rigidbody_under_robot_root" + except Exception: + self._debug_env0_probe_status = "resolve_exception" + return None + return None + + def _get_env0_fabric_probe_position(self) -> tuple[float, float, float] | None: + """Read env_0 probe body world translation from Fabric backend.""" + body_path = self._resolve_env0_fabric_probe_body_path() + if not body_path: + return None + return self._get_fabric_position_for_path(body_path) + + def _get_fabric_position_for_path(self, body_path: str) -> tuple[float, float, float] | None: + """Read a body world translation from Fabric backend.""" + try: + import isaacsim.core.experimental.utils.backend as backend_utils + import isaacsim.core.experimental.utils.prim as prim_utils + import numpy as np + + with backend_utils.use_backend("fabric"): + world_matrix = prim_utils.get_prim_attribute_value(body_path, "omni:fabric:worldMatrix") + translation = np.array(world_matrix.ExtractTranslation(), dtype=float) + self._debug_env0_probe_status = "fabric_read_ok" + return (float(translation[0]), float(translation[1]), float(translation[2])) + except Exception: + self._debug_env0_probe_status = "fabric_read_exception" + return None + + def _get_env0_root_view_position(self) -> tuple[float, float, float] | None: + """Read env_0 articulation root position directly from PhysX root_view.""" + try: + root_transforms = self.robot.root_view.get_root_transforms() + root_transforms_t = wp.to_torch(root_transforms) + if root_transforms_t.ndim >= 2 and root_transforms_t.shape[1] >= 3 and root_transforms_t.shape[0] > 0: + return ( + float(root_transforms_t[0, 0].item()), + float(root_transforms_t[0, 1].item()), + float(root_transforms_t[0, 2].item()), + ) + except Exception: + return None + return None + class NormalVelocityCommand(UniformVelocityCommand): """Command generator that generates a velocity command in SE(2) from a normal distribution. diff --git a/source/isaaclab/isaaclab/envs/ui/base_env_window.py b/source/isaaclab/isaaclab/envs/ui/base_env_window.py index 36b1c0fab1c9..d22b1870b8d8 100644 --- a/source/isaaclab/isaaclab/envs/ui/base_env_window.py +++ b/source/isaaclab/isaaclab/envs/ui/base_env_window.py @@ -225,14 +225,14 @@ def _build_viewer_frame(self): self.ui_window_elements["viewer_eye"] = isaacsim.gui.components.ui_utils.xyz_builder( label="Camera Eye", tooltip="Modify the XYZ location of the viewer eye.", - default_val=self.env.cfg.viewer.eye, + default_val=self.env.cfg.viewer.position, step=0.1, on_value_changed_fn=[self._set_viewer_location_fn] * 3, ) self.ui_window_elements["viewer_lookat"] = isaacsim.gui.components.ui_utils.xyz_builder( label="Camera Target", tooltip="Modify the XYZ location of the viewer target.", - default_val=self.env.cfg.viewer.lookat, + default_val=self.env.cfg.viewer.target_position, step=0.1, on_value_changed_fn=[self._set_viewer_location_fn] * 3, ) diff --git a/source/isaaclab/isaaclab/envs/ui/viewport_camera_controller.py b/source/isaaclab/isaaclab/envs/ui/viewport_camera_controller.py index 4126d7b74735..3b25e77246bc 100644 --- a/source/isaaclab/isaaclab/envs/ui/viewport_camera_controller.py +++ b/source/isaaclab/isaaclab/envs/ui/viewport_camera_controller.py @@ -50,9 +50,9 @@ def __init__(self, env: ManagerBasedEnv | DirectRLEnv, cfg: ViewerCfg): # store inputs self._env = env self._cfg = copy.deepcopy(cfg) - # cast viewer eye and look-at to numpy arrays - self.default_cam_eye = np.array(self._cfg.eye, dtype=float) - self.default_cam_lookat = np.array(self._cfg.lookat, dtype=float) + # cast viewer position and target to numpy arrays + self.default_cam_eye = np.array(self._cfg.position, dtype=float) + self.default_cam_lookat = np.array(self._cfg.target_position, dtype=float) # set the camera origins if self.cfg.origin_type == "env": diff --git a/source/isaaclab/isaaclab/sim/simulation_context.py b/source/isaaclab/isaaclab/sim/simulation_context.py index a82b3c662d16..404059c6c243 100644 --- a/source/isaaclab/isaaclab/sim/simulation_context.py +++ b/source/isaaclab/isaaclab/sim/simulation_context.py @@ -35,6 +35,7 @@ from .spawners import DomeLightCfg, GroundPlaneCfg logger = logging.getLogger(__name__) +_VIS_DEBUG_ENABLED = os.getenv("ISAACLAB_VIS_DEBUG", "0").lower() in {"1", "true", "yes", "on"} # Visualizer type names (CLI and config). App launcher parses CSV and stores as a space-separated setting. _VISUALIZER_TYPES = ("newton", "rerun", "viser", "kit") @@ -188,6 +189,8 @@ def __init__(self, cfg: SimulationCfg | None = None): # Monotonic physics-step counter used by camera sensors for self._physics_step_count: int = 0 + self._debug_last_pause_signature: tuple[bool, bool, bool, int] | None = None + self._debug_period_steps = 120 type(self)._instance = self # Mark as valid singleton only after successful init @@ -681,6 +684,19 @@ def update_visualizers(self, dt: float) -> None: if not self._visualizers: return + if _VIS_DEBUG_ENABLED and ( + self._visualizer_step_counter % self._debug_period_steps == 0 or self._visualizer_step_counter < 5 + ): + logger.warning( + "[VIS-DEBUG][SimulationContext.update_visualizers] step=%d dt=%.4f sim_playing=%s " + "visualizer_count=%d requires_forward=%s", + self._visualizer_step_counter, + dt, + self.is_playing(), + len(self._visualizers), + self._should_forward_before_visualizer_update(), + ) + self.update_scene_data_provider() visualizers_to_remove = [] @@ -699,6 +715,23 @@ def update_visualizers(self, dt: float) -> None: viz.step(0.0) continue while viz.is_training_paused() and viz.is_running(): + if _VIS_DEBUG_ENABLED: + pause_signature = ( + bool(self.is_playing()), + bool(viz.is_running()), + bool(viz.is_training_paused()), + id(viz), + ) + if pause_signature != self._debug_last_pause_signature: + logger.warning( + "[VIS-DEBUG][SimulationContext.update_visualizers] training paused loop: " + "viz=%s sim_playing=%s viz_running=%s viz_training_paused=%s", + type(viz).__name__, + self.is_playing(), + viz.is_running(), + viz.is_training_paused(), + ) + self._debug_last_pause_signature = pause_signature viz.step(0.0) viz.step(dt) except Exception as exc: diff --git a/source/isaaclab/test/envs/test_color_randomization.py b/source/isaaclab/test/envs/test_color_randomization.py index a7edda7036c1..cee00ee90aa5 100644 --- a/source/isaaclab/test/envs/test_color_randomization.py +++ b/source/isaaclab/test/envs/test_color_randomization.py @@ -126,8 +126,8 @@ class CartpoleEnvCfg(ManagerBasedEnvCfg): def __post_init__(self): """Post initialization.""" # viewer settings - self.viewer.eye = [4.5, 0.0, 6.0] - self.viewer.lookat = [0.0, 0.0, 2.0] + self.viewer.position = [4.5, 0.0, 6.0] + self.viewer.target_position = [0.0, 0.0, 2.0] # step settings self.decimation = 4 # env step every 4 sim steps: 200Hz / 4 = 50Hz # simulation settings diff --git a/source/isaaclab/test/envs/test_texture_randomization.py b/source/isaaclab/test/envs/test_texture_randomization.py index b5fe287c48ce..256c9f2271ff 100644 --- a/source/isaaclab/test/envs/test_texture_randomization.py +++ b/source/isaaclab/test/envs/test_texture_randomization.py @@ -172,8 +172,8 @@ class CartpoleEnvCfg(ManagerBasedEnvCfg): def __post_init__(self): """Post initialization.""" # viewer settings - self.viewer.eye = [4.5, 0.0, 6.0] - self.viewer.lookat = [0.0, 0.0, 2.0] + self.viewer.position = [4.5, 0.0, 6.0] + self.viewer.target_position = [0.0, 0.0, 2.0] # step settings self.decimation = 4 # env step every 4 sim steps: 200Hz / 4 = 50Hz # simulation settings diff --git a/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py b/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py index 2298cbbb2d70..a6c01a4e837b 100644 --- a/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py +++ b/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py @@ -42,6 +42,7 @@ __all__ = ["IsaacEvents", "PhysxManager"] logger = logging.getLogger(__name__) +_VIS_DEBUG_ENABLED = os.getenv("ISAACLAB_VIS_DEBUG", "0").lower() in {"1", "true", "yes", "on"} class IsaacEvents(Enum): @@ -175,6 +176,8 @@ class PhysxManager(PhysicsManager): _subscriptions: ClassVar[dict[str, Any]] = {} _fabric: ClassVar[Any] = None _update_fabric: ClassVar[Callable[[float, float], None] | None] = None + _debug_forward_counter: ClassVar[int] = 0 + _debug_last_forward_signature: ClassVar[tuple[bool, bool, bool] | None] = None _anim_recorder: ClassVar[AnimationRecorder | None] = None _callback_exception: ClassVar[Exception | None] = None @@ -244,9 +247,29 @@ def forward(cls) -> None: """Update articulation kinematics and fabric for rendering.""" sim = PhysicsManager._sim if cls._fabric is not None and cls._update_fabric is not None: - if cls._view is not None and sim is not None and sim.is_playing(): + sim_is_playing = bool(sim is not None and sim.is_playing()) + timeline_playing = bool(cls._timeline is not None and cls._timeline.is_playing()) + has_view = bool(cls._view is not None) + did_update_kinematics = False + if has_view and sim_is_playing: cls._view.update_articulations_kinematic() + did_update_kinematics = True cls._update_fabric(0.0, 0.0) + cls._debug_forward_counter += 1 + if _VIS_DEBUG_ENABLED: + signature = (sim_is_playing, has_view, did_update_kinematics) + if cls._debug_last_forward_signature != signature or (cls._debug_forward_counter % 120 == 0): + logger.warning( + "[VIS-DEBUG][PhysxManager.forward] count=%d sim_playing=%s timeline_playing=%s has_view=%s " + "updated_kinematics=%s updated_fabric=%s", + cls._debug_forward_counter, + sim_is_playing, + timeline_playing, + has_view, + did_update_kinematics, + True, + ) + cls._debug_last_forward_signature = signature @classmethod def step(cls) -> None: diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/classic/cartpole/cartpole_camera_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/classic/cartpole/cartpole_camera_env_cfg.py index dfccd3d36890..be0c9aa99869 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/classic/cartpole/cartpole_camera_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/classic/cartpole/cartpole_camera_env_cfg.py @@ -142,8 +142,8 @@ def __post_init__(self): # remove ground as it obstructs the camera self.scene.ground = None # viewer settings - self.viewer.eye = (7.0, 0.0, 2.5) - self.viewer.lookat = (0.0, 0.0, 2.5) + self.viewer.position = (7.0, 0.0, 2.5) + self.viewer.target_position = (0.0, 0.0, 2.5) @configclass @@ -158,8 +158,8 @@ def __post_init__(self): # remove ground as it obstructs the camera self.scene.ground = None # viewer settings - self.viewer.eye = (7.0, 0.0, 2.5) - self.viewer.lookat = (0.0, 0.0, 2.5) + self.viewer.position = (7.0, 0.0, 2.5) + self.viewer.target_position = (0.0, 0.0, 2.5) @configclass 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 660be6136e22..78010c67024b 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 @@ -202,7 +202,7 @@ def __post_init__(self) -> None: self.decimation = 2 self.episode_length_s = 5 # viewer settings - self.viewer.eye = (8.0, 0.0, 5.0) + self.viewer.position = (8.0, 0.0, 5.0) # simulation settings self.sim.dt = 1 / 120 self.sim.render_interval = self.decimation 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 2714b2cd40a2..31b4e66bd4f6 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 @@ -335,6 +335,6 @@ def __post_init__(self): # general settings self.decimation = 1 self.episode_length_s = 8.0 - self.viewer.eye = (-2.0, 2.0, 2.0) - self.viewer.lookat = (0.8, 0.0, 0.5) + self.viewer.position = (-2.0, 2.0, 2.0) + self.viewer.target_position = (0.8, 0.0, 0.5) # simulation settings are defined in CabinetSimCfg (dt/physics vary per backend) 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 8adcddcb8b0f..771d5c2b597c 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,8 +275,8 @@ def __post_init__(self): # general settings self.decimation = 1 self.episode_length_s = 8.0 - self.viewer.eye = (-2.0, 2.0, 2.0) - self.viewer.lookat = (0.8, 0.0, 0.5) + self.viewer.position = (-2.0, 2.0, 2.0) + self.viewer.target_position = (0.8, 0.0, 0.5) # simulation settings self.sim.dt = 1 / 60 # 60Hz self.sim.render_interval = self.decimation diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/deploy/gear_assembly/gear_assembly_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/deploy/gear_assembly/gear_assembly_env_cfg.py index 6a3fc7f080f4..32be1cf8fd2f 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/deploy/gear_assembly/gear_assembly_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/deploy/gear_assembly/gear_assembly_env_cfg.py @@ -312,7 +312,7 @@ def __post_init__(self): """Post initialization.""" # general settings self.episode_length_s = 6.66 - self.viewer.eye = (3.5, 3.5, 3.5) + self.viewer.position = (3.5, 3.5, 3.5) # simulation settings self.decimation = 4 self.sim.render_interval = self.decimation 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 018ef3a49c9c..d26ff7555cd1 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 @@ -210,6 +210,6 @@ def __post_init__(self): self.decimation = 2 self.sim.render_interval = self.decimation self.episode_length_s = 12.0 - self.viewer.eye = (3.5, 3.5, 3.5) + self.viewer.position = (3.5, 3.5, 3.5) # simulation settings self.sim.dt = 1.0 / 120.0 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 891d166c8e1a..96a802ec8eb2 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 @@ -345,4 +345,4 @@ def __post_init__(self): self.sim.dt = 1.0 / 120.0 self.sim.render_interval = self.decimation # change viewer settings - self.viewer.eye = (2.0, 2.0, 2.0) + self.viewer.position = (2.0, 2.0, 2.0) 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 4d70b1571a5f..66cae30fc3a0 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 @@ -202,8 +202,8 @@ def __post_init__(self): ) # set viewer to see the whole scene - self.viewer.eye = [1.5, -1.0, 1.5] - self.viewer.lookat = [0.5, 0.0, 0.0] + self.viewer.position = [1.5, -1.0, 1.5] + self.viewer.target_position = [0.5, 0.0, 0.0] """ 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 f111cb41cd20..a667d3cb176f 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 @@ -330,6 +330,6 @@ def __post_init__(self): self.decimation = 2 self.sim.render_interval = self.decimation self.episode_length_s = 24.0 - self.viewer.eye = (3.5, 3.5, 3.5) + self.viewer.position = (3.5, 3.5, 3.5) # simulation settings self.sim.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 efde276b7dc6..c375da063a5f 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 @@ -243,6 +243,6 @@ def __post_init__(self): self.decimation = 2 self.sim.render_interval = self.decimation self.episode_length_s = 12.0 - self.viewer.eye = (3.5, 3.5, 3.5) + self.viewer.position = (3.5, 3.5, 3.5) # simulation settings self.sim.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 3bf9cc0443fc..1c02e939f44a 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 @@ -252,7 +252,7 @@ def __post_init__(self): self.decimation = 2 self.sim.render_interval = self.decimation self.episode_length_s = 12.0 - self.viewer.eye = (3.5, 3.5, 3.5) + self.viewer.position = (3.5, 3.5, 3.5) # simulation settings self.sim.dt = 1.0 / 60.0 self.sim.physics = ReachPhysicsCfg() diff --git a/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualizer.py b/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualizer.py index d1def2f06bc7..e594dd541efc 100644 --- a/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualizer.py +++ b/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualizer.py @@ -9,6 +9,7 @@ import asyncio import logging +import os from typing import TYPE_CHECKING from pxr import UsdGeom @@ -18,6 +19,7 @@ from .kit_visualizer_cfg import KitVisualizerCfg logger = logging.getLogger(__name__) +_VIS_DEBUG_ENABLED = os.getenv("ISAACLAB_VIS_DEBUG", "0").lower() in {"1", "true", "yes", "on"} if TYPE_CHECKING: from isaaclab.physics import BaseSceneDataProvider @@ -46,6 +48,9 @@ def __init__(self, cfg: KitVisualizerCfg): # user-switching the GUI viewport to a sensor camera does not corrupt the sensor's prim. self._controlled_camera_path: str | None = None self._runtime_headless = bool(cfg.headless) + self._debug_last_step_state: tuple[bool, bool, bool | None] | None = None + self._debug_period_steps = 120 + self._last_timeline_playing: bool | None = None # ---- Lifecycle ------------------------------------------------------------------------ @@ -105,6 +110,7 @@ def step(self, dt: float) -> None: try: import carb.settings import omni.kit.app + import omni.timeline app = omni.kit.app.get_app() if app is not None and app.is_running(): @@ -112,12 +118,43 @@ def step(self, dt: float) -> None: settings = carb.settings.get_settings() play_simulations_path = "/app/player/playSimulations" previous_play_simulations = None if settings is None else settings.get(play_simulations_path) - should_restore = bool(previous_play_simulations) - if should_restore: - settings.set_bool(play_simulations_path, False) + timeline = omni.timeline.get_timeline_interface() + timeline_playing = bool(timeline is not None and timeline.is_playing()) + timeline_stopped = bool(timeline is not None and timeline.is_stopped()) + timeline_pause_state = (not timeline_playing) and (not timeline_stopped) + should_temporarily_pause = bool(previous_play_simulations) + did_app_update = False + try: + # Prevent app.update() from stepping physics. SimulationContext owns stepping. + if should_temporarily_pause and settings is not None: + settings.set_bool(play_simulations_path, False) app.update() - if should_restore: - settings.set_bool(play_simulations_path, True) + did_app_update = True + finally: + if should_temporarily_pause and settings is not None: + settings.set_bool(play_simulations_path, True) + + if _VIS_DEBUG_ENABLED: + state = (timeline_playing, timeline_stopped, previous_play_simulations) + if ( + self._debug_last_step_state != state + or (self._step_counter % self._debug_period_steps == 0) + or not did_app_update + ): + logger.warning( + "[VIS-DEBUG][KitVisualizer.step] step=%d dt=%.4f timeline_playing=%s timeline_stopped=%s " + "playSim_before=%s playSim_target=%s timeline_paused=%s app_update=%s", + self._step_counter, + dt, + timeline_playing, + timeline_stopped, + previous_play_simulations, + bool(not should_temporarily_pause), + timeline_pause_state, + did_app_update, + ) + self._debug_last_step_state = state + self._last_timeline_playing = timeline_playing except (ImportError, AttributeError) as exc: logger.debug("[KitVisualizer] App update skipped: %s", exc) From 46b03dc201e9bc14db554b3f72203952f0f1ef4a Mon Sep 17 00:00:00 2001 From: Matthew Trepte Date: Wed, 1 Apr 2026 22:19:25 +0000 Subject: [PATCH 08/11] update camera_position/camera_target_position -> eye/lookat --- docs/source/features/visualization.rst | 20 +- source/isaaclab/isaaclab/app/app_launcher.py | 21 +- source/isaaclab/isaaclab/envs/common.py | 6 +- .../isaaclab/isaaclab/envs/direct_marl_env.py | 29 +-- .../isaaclab/isaaclab/envs/direct_rl_env.py | 29 +-- .../isaaclab/envs/manager_based_env.py | 4 +- .../isaaclab/envs/manager_based_rl_env.py | 24 +-- .../envs/mdp/commands/velocity_command.py | 187 ------------------ .../isaaclab/envs/ui/base_env_window.py | 4 +- .../envs/ui/viewport_camera_controller.py | 6 +- .../isaaclab/sim/simulation_context.py | 62 +++--- .../isaaclab/visualizers/base_visualizer.py | 21 ++ .../isaaclab/visualizers/visualizer_cfg.py | 18 +- .../test/envs/test_color_randomization.py | 4 +- .../test/envs/test_texture_randomization.py | 4 +- .../isaaclab_physx/physics/physx_manager.py | 25 +-- .../cartpole/cartpole_camera_env_cfg.py | 8 +- .../classic/cartpole/cartpole_env_cfg.py | 2 +- .../manipulation/cabinet/cabinet_env_cfg.py | 4 +- .../config/openarm/cabinet_openarm_env_cfg.py | 4 +- .../gear_assembly/gear_assembly_env_cfg.py | 2 +- .../deploy/reach/reach_env_cfg.py | 2 +- .../manipulation/inhand/inhand_env_cfg.py | 2 +- .../agibot/place_toy2box_rmp_rel_env_cfg.py | 4 +- .../bimanual/reach_openarm_bi_env_cfg.py | 2 +- .../unimanual/reach_openarm_uni_env_cfg.py | 2 +- .../manipulation/reach/reach_env_cfg.py | 2 +- .../kit/kit_visualizer.py | 83 +++----- .../kit/kit_visualizer_cfg.py | 14 ++ .../newton/newton_visualizer.py | 16 +- .../rerun/rerun_visualizer.py | 12 +- .../viser/viser_visualizer.py | 12 +- 32 files changed, 206 insertions(+), 429 deletions(-) diff --git a/docs/source/features/visualization.rst b/docs/source/features/visualization.rst index 13d573308efb..3f60dfee485a 100644 --- a/docs/source/features/visualization.rst +++ b/docs/source/features/visualization.rst @@ -109,12 +109,12 @@ You can also configure custom visualizers in the code by defining ``VisualizerCf dock_position="SAME", window_width=1280, window_height=720, - camera_position=(0.0, 0.0, 20.0), # high top down view - camera_target=(0.0, 0.0, 0.0), + eye=(0.0, 0.0, 20.0), # high top down view + lookat=(0.0, 0.0, 0.0), ), NewtonVisualizerCfg( - camera_position=(5.0, 5.0, 5.0), # closer quarter view - camera_target=(0.0, 0.0, 0.0), + eye=(5.0, 5.0, 5.0), # closer quarter view + lookat=(0.0, 0.0, 0.0), show_joints=True, ), RerunVisualizerCfg( @@ -201,8 +201,8 @@ Omniverse Visualizer window_height=720, # Viewport height in pixels # Camera settings - camera_position=(8.0, 8.0, 3.0), # Initial camera position (x, y, z) - camera_target=(0.0, 0.0, 0.0), # Camera look-at target + eye=(8.0, 8.0, 3.0), # Initial camera position (x, y, z) + lookat=(0.0, 0.0, 0.0), # Camera look-at target # Feature toggles enable_markers=True, # Enable visualization markers @@ -255,8 +255,8 @@ Newton Visualizer window_height=1080, # Window height in pixels # Camera settings - camera_position=(8.0, 8.0, 3.0), # Initial camera position (x, y, z) - camera_target=(0.0, 0.0, 0.0), # Camera look-at target + eye=(8.0, 8.0, 3.0), # Initial camera position (x, y, z) + lookat=(0.0, 0.0, 0.0), # Camera look-at target # Performance tuning update_frequency=1, # Update every N frames (1=every frame) @@ -303,8 +303,8 @@ Rerun Visualizer bind_address="0.0.0.0", # Endpoint host formatting/reuse checks # Camera settings - camera_position=(8.0, 8.0, 3.0), # Initial camera position (x, y, z) - camera_target=(0.0, 0.0, 0.0), # Camera look-at target + eye=(8.0, 8.0, 3.0), # Initial camera position (x, y, z) + lookat=(0.0, 0.0, 0.0), # Camera look-at target # History settings keep_historical_data=False, # Keep transforms for time scrubbing diff --git a/source/isaaclab/isaaclab/app/app_launcher.py b/source/isaaclab/isaaclab/app/app_launcher.py index 597714267c20..385c87d4a23c 100644 --- a/source/isaaclab/isaaclab/app/app_launcher.py +++ b/source/isaaclab/isaaclab/app/app_launcher.py @@ -188,6 +188,8 @@ def __init__(self, launcher_args: argparse.Namespace | dict | None = None, **kwa self._offscreen_render: bool # 0: Disabled, 1: Enabled self._sim_experience_file: str # Experience file to load self._visualizer_max_worlds: int | None # Optional max worlds override for Newton-based visualizers + self._video_enabled: bool # Whether --video recording is enabled + self._video_auto_start_kit: bool # Whether headless video should auto-inject Kit visualizer # Exposed to train scripts self.device_id: int # device ID for GPU simulation (defaults to 0) @@ -842,14 +844,28 @@ def _resolve_xr_settings(self, launcher_args: dict): def _resolve_viewport_settings(self, launcher_args: dict): """Resolve viewport related settings.""" + self._video_enabled = bool(launcher_args.get("video", False)) # Check if we can disable the viewport to improve performance # This should only happen if we are running headless and do not require livestreaming or video recording # This is different from offscreen_render because this only affects the default viewport and # not other render-products in the scene self._render_viewport = True - if self._headless and not self._livestream and not launcher_args.get("video", False): + if self._headless and not self._livestream and not self._video_enabled: self._render_viewport = False + # Auto-start a headless Kit visualizer when recording video without an explicit + # visualizer selection. This ensures app.update() is pumped and camera updates + # can be forwarded from viewer settings. + has_explicit_kit = self._cli_visualizer_explicit and "kit" in set(self._cli_visualizer_types) + self._video_auto_start_kit = ( + self._video_enabled + and self._headless + and not self._livestream + and not self._xr + and not self._cli_visualizer_disable_all + and not has_explicit_kit + ) + # hide_ui flag launcher_args["hide_ui"] = False if self._headless and not self._livestream: @@ -1069,6 +1085,9 @@ def _load_extensions(self): # (no Kit GUI) the AR profile must be enabled programmatically so that # the OpenXR session starts without user interaction settings.set_bool("/isaaclab/xr/auto_start", self._headless and self._xr) + # set setting to indicate video recording mode and optional Kit auto-start + settings.set_bool("/isaaclab/video/enabled", self._video_enabled) + settings.set_bool("/isaaclab/video/auto_start_kit", self._video_auto_start_kit) # set setting to indicate no RTX sensors are used (set to True when RTX sensor is created) settings.set_bool("/isaaclab/render/rtx_sensors", False) diff --git a/source/isaaclab/isaaclab/envs/common.py b/source/isaaclab/isaaclab/envs/common.py index f8bc39d4f6b2..cf1206908c8f 100644 --- a/source/isaaclab/isaaclab/envs/common.py +++ b/source/isaaclab/isaaclab/envs/common.py @@ -21,10 +21,10 @@ class ViewerCfg: """Configuration of the scene viewport camera.""" - position: tuple[float, float, float] = (7.5, 17.5, 17.5) + eye: tuple[float, float, float] = (7.5, 7.5, 117.5) """Initial camera position (in m). Default is (7.5, 7.5, 7.5).""" - target_position: tuple[float, float, float] = (0.0, 0.0, 5.0) + lookat: tuple[float, float, float] = (0.0, 0.0, 0.0) """Initial camera target position (in m). Default is (0.0, 0.0, 0.0).""" cam_prim_path: str = "/OmniverseKit_Persp" @@ -38,7 +38,7 @@ class ViewerCfg: """ origin_type: Literal["world", "env", "asset_root", "asset_body"] = "world" - """The frame in which the camera position and target are defined in. Default is "world". + """The frame in which the camera eye and lookat are defined in. Default is "world". Available options are: diff --git a/source/isaaclab/isaaclab/envs/direct_marl_env.py b/source/isaaclab/isaaclab/envs/direct_marl_env.py index 4e0718be9e1a..3d028a2a7ba9 100644 --- a/source/isaaclab/isaaclab/envs/direct_marl_env.py +++ b/source/isaaclab/isaaclab/envs/direct_marl_env.py @@ -152,7 +152,9 @@ def _init_sim(self, render_mode: str | None = None, **kwargs): # non-rendering modes. # Initialize when GUI is available OR when visualizers are active (headless rendering) # Visualizers support camera updates via sim.set_camera_view() which forwards to all active visualizers - has_visualizers = bool(self.sim.get_setting("/isaaclab/visualizer/types")) + has_visualizers = bool(self.sim.get_setting("/isaaclab/visualizer/types")) or bool( + self.sim.get_setting("/isaaclab/video/auto_start_kit") + ) if self.sim.has_gui or has_visualizers: self.viewport_camera_controller = ViewportCameraController(self, self.cfg.viewer) else: @@ -522,7 +524,10 @@ def render(self, recompute: bool = False) -> np.ndarray | None: return None elif self.render_mode == "rgb_array": # check that if any render could have happened - if not self.sim.has_gui and not self.sim.has_offscreen_render: + has_visualizers = bool(self.sim.get_setting("/isaaclab/visualizer/types")) or bool( + self.sim.get_setting("/isaaclab/video/auto_start_kit") + ) + if not (self.sim.has_gui or self.sim.has_offscreen_render or has_visualizers): raise RuntimeError( f"Cannot render '{self.render_mode}' - no GUI and offscreen rendering not enabled." " If running headless, make sure --enable_cameras is set." @@ -532,8 +537,6 @@ def render(self, recompute: bool = False) -> np.ndarray | None: import omni.replicator.core as rep camera_prim_path = self.cfg.viewer.cam_prim_path - self._set_rgb_array_camera_view(camera_prim_path) - # create render product self._render_product = rep.create.render_product(camera_prim_path, self.cfg.viewer.resolution) # create rgb annotator -- used to read data from the render product @@ -554,24 +557,6 @@ def render(self, recompute: bool = False) -> np.ndarray | None: f"Render mode '{self.render_mode}' is not supported. Please use: {self.metadata['render_modes']}." ) - def _set_rgb_array_camera_view(self, camera_prim_path: str) -> None: - """Set perspective camera pose for rgb-array capture (headless-safe).""" - try: - import isaacsim.core.utils.viewports as isaacsim_viewports - - viewer_origin = torch.zeros(3, dtype=torch.float32) - if self.cfg.viewer.origin_type == "env" and self.num_envs > 0: - env_index = max(0, min(self.cfg.viewer.env_index, self.num_envs - 1)) - viewer_origin = self.scene.env_origins[env_index].detach().cpu().float() - else: - viewer_origin = viewer_origin.cpu() - - cam_eye = (viewer_origin + torch.tensor(self.cfg.viewer.position, dtype=torch.float32)).tolist() - cam_target = (viewer_origin + torch.tensor(self.cfg.viewer.target_position, dtype=torch.float32)).tolist() - isaacsim_viewports.set_camera_view(eye=cam_eye, target=cam_target, camera_prim_path=camera_prim_path) - except Exception as exc: - logger.debug("Failed to set rgb-array camera view for '%s': %s", camera_prim_path, exc) - def close(self): """Cleanup for the environment.""" if not self._is_closed: diff --git a/source/isaaclab/isaaclab/envs/direct_rl_env.py b/source/isaaclab/isaaclab/envs/direct_rl_env.py index 5c1e24ae8a45..6ba9fbae4e58 100644 --- a/source/isaaclab/isaaclab/envs/direct_rl_env.py +++ b/source/isaaclab/isaaclab/envs/direct_rl_env.py @@ -157,7 +157,9 @@ def _init_sim(self, render_mode: str | None = None, **kwargs): # non-rendering modes. # Initialize when GUI is available OR when visualizers are active (headless rendering) # Visualizers support camera updates via sim.set_camera_view() which forwards to all active visualizers - has_visualizers = bool(self.sim.get_setting("/isaaclab/visualizer/types")) + has_visualizers = bool(self.sim.get_setting("/isaaclab/visualizer/types")) or bool( + self.sim.get_setting("/isaaclab/video/auto_start_kit") + ) if self.sim.has_gui or has_visualizers: self.viewport_camera_controller = ViewportCameraController(self, self.cfg.viewer) else: @@ -490,7 +492,10 @@ def render(self, recompute: bool = False) -> np.ndarray | None: return None elif self.render_mode == "rgb_array": # check that if any render could have happened - if not self.sim.has_gui and not self.sim.has_offscreen_render: + has_visualizers = bool(self.sim.get_setting("/isaaclab/visualizer/types")) or bool( + self.sim.get_setting("/isaaclab/video/auto_start_kit") + ) + if not (self.sim.has_gui or self.sim.has_offscreen_render or has_visualizers): raise RuntimeError( f"Cannot render '{self.render_mode}' - no GUI and offscreen rendering not enabled." " If running headless, make sure --enable_cameras is set." @@ -500,8 +505,6 @@ def render(self, recompute: bool = False) -> np.ndarray | None: import omni.replicator.core as rep camera_prim_path = self.cfg.viewer.cam_prim_path - self._set_rgb_array_camera_view(camera_prim_path) - # create render product self._render_product = rep.create.render_product(camera_prim_path, self.cfg.viewer.resolution) # create rgb annotator -- used to read data from the render product @@ -522,24 +525,6 @@ def render(self, recompute: bool = False) -> np.ndarray | None: f"Render mode '{self.render_mode}' is not supported. Please use: {self.metadata['render_modes']}." ) - def _set_rgb_array_camera_view(self, camera_prim_path: str) -> None: - """Set perspective camera pose for rgb-array capture (headless-safe).""" - try: - import isaacsim.core.utils.viewports as isaacsim_viewports - - viewer_origin = torch.zeros(3, dtype=torch.float32) - if self.cfg.viewer.origin_type == "env" and self.num_envs > 0: - env_index = max(0, min(self.cfg.viewer.env_index, self.num_envs - 1)) - viewer_origin = self.scene.env_origins[env_index].detach().cpu().float() - else: - viewer_origin = viewer_origin.cpu() - - cam_eye = (viewer_origin + torch.tensor(self.cfg.viewer.position, dtype=torch.float32)).tolist() - cam_target = (viewer_origin + torch.tensor(self.cfg.viewer.target_position, dtype=torch.float32)).tolist() - isaacsim_viewports.set_camera_view(eye=cam_eye, target=cam_target, camera_prim_path=camera_prim_path) - except Exception as exc: - logger.debug("Failed to set rgb-array camera view for '%s': %s", camera_prim_path, exc) - def close(self): """Cleanup for the environment.""" if not self._is_closed: diff --git a/source/isaaclab/isaaclab/envs/manager_based_env.py b/source/isaaclab/isaaclab/envs/manager_based_env.py index 3f003bfeb184..a8d201b3a966 100644 --- a/source/isaaclab/isaaclab/envs/manager_based_env.py +++ b/source/isaaclab/isaaclab/envs/manager_based_env.py @@ -167,7 +167,9 @@ def _init_sim(self): # non-rendering modes. # Initialize when GUI is available OR when visualizers are active (headless rendering) # Visualizers support camera updates via sim.set_camera_view() which forwards to all active visualizers - has_visualizers = bool(self.sim.get_setting("/isaaclab/visualizer/types")) + has_visualizers = bool(self.sim.get_setting("/isaaclab/visualizer/types")) or bool( + self.sim.get_setting("/isaaclab/video/auto_start_kit") + ) if self.sim.has_gui or has_visualizers: self.viewport_camera_controller = ViewportCameraController(self, self.cfg.viewer) else: diff --git a/source/isaaclab/isaaclab/envs/manager_based_rl_env.py b/source/isaaclab/isaaclab/envs/manager_based_rl_env.py index d3f9723b0838..45c08746c762 100644 --- a/source/isaaclab/isaaclab/envs/manager_based_rl_env.py +++ b/source/isaaclab/isaaclab/envs/manager_based_rl_env.py @@ -275,7 +275,9 @@ def render(self, recompute: bool = False) -> np.ndarray | None: elif self.render_mode == "rgb_array": # check that if any render could have happened # Check for GUI, offscreen rendering, or visualizers - has_visualizers = bool(self.sim.get_setting("/isaaclab/visualizer/types")) + has_visualizers = bool(self.sim.get_setting("/isaaclab/visualizer/types")) or bool( + self.sim.get_setting("/isaaclab/video/auto_start_kit") + ) if not (self.sim.has_gui or self.sim.has_offscreen_render or has_visualizers): raise RuntimeError( f"Cannot render '{self.render_mode}' - no GUI and offscreen rendering not enabled." @@ -286,8 +288,6 @@ def render(self, recompute: bool = False) -> np.ndarray | None: import omni.replicator.core as rep camera_prim_path = self.cfg.viewer.cam_prim_path - self._set_rgb_array_camera_view(camera_prim_path) - # create render product self._render_product = rep.create.render_product(camera_prim_path, self.cfg.viewer.resolution) # create rgb annotator -- used to read data from the render product @@ -308,24 +308,6 @@ def render(self, recompute: bool = False) -> np.ndarray | None: f"Render mode '{self.render_mode}' is not supported. Please use: {self.metadata['render_modes']}." ) - def _set_rgb_array_camera_view(self, camera_prim_path: str) -> None: - """Set perspective camera pose for rgb-array capture (headless-safe).""" - try: - import isaacsim.core.utils.viewports as isaacsim_viewports - - viewer_origin = torch.zeros(3, dtype=torch.float32) - if self.cfg.viewer.origin_type == "env" and self.num_envs > 0: - env_index = max(0, min(self.cfg.viewer.env_index, self.num_envs - 1)) - viewer_origin = self.scene.env_origins[env_index].detach().cpu().float() - else: - viewer_origin = viewer_origin.cpu() - - cam_eye = (viewer_origin + torch.tensor(self.cfg.viewer.position, dtype=torch.float32)).tolist() - cam_target = (viewer_origin + torch.tensor(self.cfg.viewer.target_position, dtype=torch.float32)).tolist() - isaacsim_viewports.set_camera_view(eye=cam_eye, target=cam_target, camera_prim_path=camera_prim_path) - except Exception as exc: - logger.debug("Failed to set rgb-array camera view for '%s': %s", camera_prim_path, exc) - def close(self): if not self._is_closed: # destructor is order-sensitive diff --git a/source/isaaclab/isaaclab/envs/mdp/commands/velocity_command.py b/source/isaaclab/isaaclab/envs/mdp/commands/velocity_command.py index 4019917ee97d..efd7278d2f1f 100644 --- a/source/isaaclab/isaaclab/envs/mdp/commands/velocity_command.py +++ b/source/isaaclab/isaaclab/envs/mdp/commands/velocity_command.py @@ -8,8 +8,6 @@ from __future__ import annotations import logging -import os -import re from collections.abc import Sequence from typing import TYPE_CHECKING @@ -28,7 +26,6 @@ # import logger logger = logging.getLogger(__name__) -_VIS_DEBUG_ENABLED = os.getenv("ISAACLAB_VIS_DEBUG", "0").lower() in {"1", "true", "yes", "on"} class UniformVelocityCommand(CommandTerm): @@ -87,9 +84,6 @@ def __init__(self, cfg: UniformVelocityCommandCfg, env: ManagerBasedEnv): self.heading_target = torch.zeros(self.num_envs, device=self.device) self.is_heading_env = torch.zeros(self.num_envs, dtype=torch.bool, device=self.device) self.is_standing_env = torch.zeros_like(self.is_heading_env) - self._debug_vis_callback_count = 0 - self._debug_env0_probe_body_path: str | None = None - self._debug_env0_probe_status: str = "uninitialized" # -- metrics self.metrics["error_vel_xy"] = torch.zeros(self.num_envs, device=self.device) self.metrics["error_vel_yaw"] = torch.zeros(self.num_envs, device=self.device) @@ -207,83 +201,6 @@ def _debug_vis_callback(self, event): # display markers self.goal_vel_visualizer.visualize(base_pos_w, vel_des_arrow_quat, vel_des_arrow_scale) self.current_vel_visualizer.visualize(base_pos_w, vel_arrow_quat, vel_arrow_scale) - self._debug_vis_callback_count += 1 - if _VIS_DEBUG_ENABLED and ( - self._debug_vis_callback_count <= 3 or self._debug_vis_callback_count % 120 == 0 - ): - mean_cmd = float(torch.linalg.norm(self.command[:, :2], dim=-1).mean().item()) - mean_vel = float(torch.linalg.norm(wp.to_torch(self.robot.data.root_lin_vel_b)[:, :2], dim=-1).mean().item()) - tensor_root_pos = wp.to_torch(self.robot.data.root_pos_w)[0].detach().cpu() - fabric_root_pos = self._get_env0_fabric_probe_position() - root_view_pos = self._get_env0_root_view_position() - robot_root = self._resolve_env0_robot_root_path() - fabric_base_pos = self._get_fabric_position_for_path(f"{robot_root}/base") if robot_root else None - fabric_trunk_pos = self._get_fabric_position_for_path(f"{robot_root}/trunk") if robot_root else None - if fabric_root_pos is not None: - fabric_root_pos_t = torch.tensor(fabric_root_pos, dtype=tensor_root_pos.dtype) - delta = torch.linalg.norm(tensor_root_pos - fabric_root_pos_t).item() - root_view_delta = None - if root_view_pos is not None: - root_view_pos_t = torch.tensor(root_view_pos, dtype=tensor_root_pos.dtype) - root_view_delta = torch.linalg.norm(tensor_root_pos - root_view_pos_t).item() - logger.warning( - "[VIS-DEBUG][UniformVelocityCommand._debug_vis_callback] count=%d mean_cmd_xy=%.4f " - "mean_vel_xy=%.4f env0_tensor_root=(%.3f, %.3f, %.3f) env0_fabric_root=(%.3f, %.3f, %.3f) " - "tensor_fabric_delta=%.5f root_view_delta=%s fabric_base=%s fabric_trunk=%s " - "probe_path=%s probe_status=%s", - self._debug_vis_callback_count, - mean_cmd, - mean_vel, - float(tensor_root_pos[0]), - float(tensor_root_pos[1]), - float(tensor_root_pos[2]), - float(fabric_root_pos_t[0]), - float(fabric_root_pos_t[1]), - float(fabric_root_pos_t[2]), - float(delta), - f"{root_view_delta:.5f}" if root_view_delta is not None else "", - ( - f"({fabric_base_pos[0]:.3f}, {fabric_base_pos[1]:.3f}, {fabric_base_pos[2]:.3f})" - if fabric_base_pos is not None - else "" - ), - ( - f"({fabric_trunk_pos[0]:.3f}, {fabric_trunk_pos[1]:.3f}, {fabric_trunk_pos[2]:.3f})" - if fabric_trunk_pos is not None - else "" - ), - self._debug_env0_probe_body_path or "", - self._debug_env0_probe_status, - ) - else: - logger.warning( - "[VIS-DEBUG][UniformVelocityCommand._debug_vis_callback] count=%d mean_cmd_xy=%.4f " - "mean_vel_xy=%.4f env0_tensor_root=(%.3f, %.3f, %.3f) env0_fabric_root= " - "root_view=%s fabric_base=%s fabric_trunk=%s probe_path=%s probe_status=%s", - self._debug_vis_callback_count, - mean_cmd, - mean_vel, - float(tensor_root_pos[0]), - float(tensor_root_pos[1]), - float(tensor_root_pos[2]), - ( - f"({root_view_pos[0]:.3f}, {root_view_pos[1]:.3f}, {root_view_pos[2]:.3f})" - if root_view_pos is not None - else "" - ), - ( - f"({fabric_base_pos[0]:.3f}, {fabric_base_pos[1]:.3f}, {fabric_base_pos[2]:.3f})" - if fabric_base_pos is not None - else "" - ), - ( - f"({fabric_trunk_pos[0]:.3f}, {fabric_trunk_pos[1]:.3f}, {fabric_trunk_pos[2]:.3f})" - if fabric_trunk_pos is not None - else "" - ), - self._debug_env0_probe_body_path or "", - self._debug_env0_probe_status, - ) """ Internal helpers. @@ -306,110 +223,6 @@ def _resolve_xy_velocity_to_arrow(self, xy_velocity: torch.Tensor) -> tuple[torc return arrow_scale, arrow_quat - def _resolve_env0_robot_root_path(self) -> str | None: - """Best-effort resolve env_0 robot root path from articulation cfg prim path.""" - prim_path = getattr(self.robot.cfg, "prim_path", None) - if not isinstance(prim_path, str) or not prim_path: - return None - path = prim_path - if "{ENV_REGEX_NS}" in path: - path = path.replace("{ENV_REGEX_NS}", "/World/envs/env_0") - path = path.replace("env_.*", "env_0") - path = re.sub(r"\.\*$", "0", path) - return path - - def _resolve_env0_fabric_probe_body_path(self) -> str | None: - """Resolve a rigid-body prim path for env_0 suitable for Fabric world-matrix probing.""" - if self._debug_env0_probe_body_path is not None: - return self._debug_env0_probe_body_path - try: - from pxr import UsdPhysics - - stage = self._env.sim.stage - if stage is None: - self._debug_env0_probe_status = "no_stage" - return None - robot_root = self._resolve_env0_robot_root_path() - if not robot_root: - self._debug_env0_probe_status = "no_robot_root_path" - return None - root_prim = stage.GetPrimAtPath(robot_root) - if not root_prim.IsValid(): - self._debug_env0_probe_status = f"invalid_robot_root:{robot_root}" - return None - - # First try common body names directly under Robot to avoid brittle traversal assumptions. - fallback_candidates = [ - f"{robot_root}/base", - f"{robot_root}/base_link", - f"{robot_root}/trunk", - f"{robot_root}/pelvis", - ] - for candidate in fallback_candidates: - prim = stage.GetPrimAtPath(candidate) - if prim.IsValid() and prim.HasAPI(UsdPhysics.RigidBodyAPI): - self._debug_env0_probe_body_path = candidate - self._debug_env0_probe_status = "resolved_fallback_candidate" - return self._debug_env0_probe_body_path - - preferred_names = {"base", "base_link", "trunk", "pelvis"} - for prim in root_prim.Traverse(): - if not prim.IsValid() or not prim.HasAPI(UsdPhysics.RigidBodyAPI): - continue - if prim.GetName() in preferred_names: - self._debug_env0_probe_body_path = prim.GetPath().pathString - self._debug_env0_probe_status = "resolved_traverse_preferred" - return self._debug_env0_probe_body_path - for prim in root_prim.Traverse(): - if prim.IsValid() and prim.HasAPI(UsdPhysics.RigidBodyAPI): - self._debug_env0_probe_body_path = prim.GetPath().pathString - self._debug_env0_probe_status = "resolved_traverse_first_rigidbody" - return self._debug_env0_probe_body_path - self._debug_env0_probe_status = "no_rigidbody_under_robot_root" - except Exception: - self._debug_env0_probe_status = "resolve_exception" - return None - return None - - def _get_env0_fabric_probe_position(self) -> tuple[float, float, float] | None: - """Read env_0 probe body world translation from Fabric backend.""" - body_path = self._resolve_env0_fabric_probe_body_path() - if not body_path: - return None - return self._get_fabric_position_for_path(body_path) - - def _get_fabric_position_for_path(self, body_path: str) -> tuple[float, float, float] | None: - """Read a body world translation from Fabric backend.""" - try: - import isaacsim.core.experimental.utils.backend as backend_utils - import isaacsim.core.experimental.utils.prim as prim_utils - import numpy as np - - with backend_utils.use_backend("fabric"): - world_matrix = prim_utils.get_prim_attribute_value(body_path, "omni:fabric:worldMatrix") - translation = np.array(world_matrix.ExtractTranslation(), dtype=float) - self._debug_env0_probe_status = "fabric_read_ok" - return (float(translation[0]), float(translation[1]), float(translation[2])) - except Exception: - self._debug_env0_probe_status = "fabric_read_exception" - return None - - def _get_env0_root_view_position(self) -> tuple[float, float, float] | None: - """Read env_0 articulation root position directly from PhysX root_view.""" - try: - root_transforms = self.robot.root_view.get_root_transforms() - root_transforms_t = wp.to_torch(root_transforms) - if root_transforms_t.ndim >= 2 and root_transforms_t.shape[1] >= 3 and root_transforms_t.shape[0] > 0: - return ( - float(root_transforms_t[0, 0].item()), - float(root_transforms_t[0, 1].item()), - float(root_transforms_t[0, 2].item()), - ) - except Exception: - return None - return None - - class NormalVelocityCommand(UniformVelocityCommand): """Command generator that generates a velocity command in SE(2) from a normal distribution. diff --git a/source/isaaclab/isaaclab/envs/ui/base_env_window.py b/source/isaaclab/isaaclab/envs/ui/base_env_window.py index d22b1870b8d8..36b1c0fab1c9 100644 --- a/source/isaaclab/isaaclab/envs/ui/base_env_window.py +++ b/source/isaaclab/isaaclab/envs/ui/base_env_window.py @@ -225,14 +225,14 @@ def _build_viewer_frame(self): self.ui_window_elements["viewer_eye"] = isaacsim.gui.components.ui_utils.xyz_builder( label="Camera Eye", tooltip="Modify the XYZ location of the viewer eye.", - default_val=self.env.cfg.viewer.position, + default_val=self.env.cfg.viewer.eye, step=0.1, on_value_changed_fn=[self._set_viewer_location_fn] * 3, ) self.ui_window_elements["viewer_lookat"] = isaacsim.gui.components.ui_utils.xyz_builder( label="Camera Target", tooltip="Modify the XYZ location of the viewer target.", - default_val=self.env.cfg.viewer.target_position, + default_val=self.env.cfg.viewer.lookat, step=0.1, on_value_changed_fn=[self._set_viewer_location_fn] * 3, ) diff --git a/source/isaaclab/isaaclab/envs/ui/viewport_camera_controller.py b/source/isaaclab/isaaclab/envs/ui/viewport_camera_controller.py index 3b25e77246bc..4126d7b74735 100644 --- a/source/isaaclab/isaaclab/envs/ui/viewport_camera_controller.py +++ b/source/isaaclab/isaaclab/envs/ui/viewport_camera_controller.py @@ -50,9 +50,9 @@ def __init__(self, env: ManagerBasedEnv | DirectRLEnv, cfg: ViewerCfg): # store inputs self._env = env self._cfg = copy.deepcopy(cfg) - # cast viewer position and target to numpy arrays - self.default_cam_eye = np.array(self._cfg.position, dtype=float) - self.default_cam_lookat = np.array(self._cfg.target_position, dtype=float) + # cast viewer eye and look-at to numpy arrays + self.default_cam_eye = np.array(self._cfg.eye, dtype=float) + self.default_cam_lookat = np.array(self._cfg.lookat, dtype=float) # set the camera origins if self.cfg.origin_type == "env": diff --git a/source/isaaclab/isaaclab/sim/simulation_context.py b/source/isaaclab/isaaclab/sim/simulation_context.py index 404059c6c243..810e5bc38807 100644 --- a/source/isaaclab/isaaclab/sim/simulation_context.py +++ b/source/isaaclab/isaaclab/sim/simulation_context.py @@ -35,7 +35,6 @@ from .spawners import DomeLightCfg, GroundPlaneCfg logger = logging.getLogger(__name__) -_VIS_DEBUG_ENABLED = os.getenv("ISAACLAB_VIS_DEBUG", "0").lower() in {"1", "true", "yes", "on"} # Visualizer type names (CLI and config). App launcher parses CSV and stores as a space-separated setting. _VISUALIZER_TYPES = ("newton", "rerun", "viser", "kit") @@ -181,7 +180,9 @@ def __init__(self, cfg: SimulationCfg | None = None): self._has_gui = bool(self.get_setting("/isaaclab/has_gui")) self._has_offscreen_render = bool(self.get_setting("/isaaclab/render/offscreen")) self._xr_enabled = bool(self.get_setting("/isaaclab/xr/enabled")) + self._video_auto_start_kit = bool(self.get_setting("/isaaclab/video/auto_start_kit")) # Note: has_rtx_sensors is NOT cached because it changes when Camera sensors are created + self._pending_camera_view: tuple[tuple[float, float, float], tuple[float, float, float]] | None = None # Simulation state self._is_playing = False @@ -189,8 +190,6 @@ def __init__(self, cfg: SimulationCfg | None = None): # Monotonic physics-step counter used by camera sensors for self._physics_step_count: int = 0 - self._debug_last_pause_signature: tuple[bool, bool, bool, int] | None = None - self._debug_period_steps = 120 type(self)._instance = self # Mark as valid singleton only after successful init @@ -537,6 +536,26 @@ def _resolve_visualizer_cfgs(self) -> list[Any]: exc, ) + # Headless video auto-start: inject a KitVisualizer when needed so that + # app.update() is pumped and viewer camera updates can be applied in + # rgb-array recording flows. + if self._video_auto_start_kit and not cli_disable_all: + has_kit = any(getattr(cfg, "visualizer_type", None) == "kit" for cfg in resolved) + if not has_kit: + try: + import importlib + + mod = importlib.import_module("isaaclab_visualizers.kit") + kit_cfg_cls = getattr(mod, "KitVisualizerCfg") + resolved.append(kit_cfg_cls(headless=True)) + logger.info("[SimulationContext] Auto-injecting KitVisualizer for headless video recording.") + except (ImportError, ModuleNotFoundError, AttributeError, TypeError) as exc: + logger.warning( + "[SimulationContext] Headless video could not auto-inject a KitVisualizer: %s. " + "Install isaaclab_visualizers[kit] or pass --visualizer kit.", + exc, + ) + return resolved def initialize_visualizers(self) -> None: @@ -580,6 +599,12 @@ def initialize_visualizers(self) -> None: exc, ) + # Replay any camera pose requested before visualizers were initialized. + if self._pending_camera_view is not None: + eye, target = self._pending_camera_view + for viz in self._visualizers: + viz.set_camera_view(eye, target) + if not self._visualizers and self._scene_data_provider is not None: close_provider = getattr(self._scene_data_provider, "close", None) if callable(close_provider): @@ -630,6 +655,7 @@ def get_rendering_dt(self) -> float: def set_camera_view(self, eye: tuple, target: tuple) -> None: """Set camera view on all visualizers that support it.""" + self._pending_camera_view = (tuple(eye), tuple(target)) for viz in self._visualizers: viz.set_camera_view(eye, target) @@ -684,19 +710,6 @@ def update_visualizers(self, dt: float) -> None: if not self._visualizers: return - if _VIS_DEBUG_ENABLED and ( - self._visualizer_step_counter % self._debug_period_steps == 0 or self._visualizer_step_counter < 5 - ): - logger.warning( - "[VIS-DEBUG][SimulationContext.update_visualizers] step=%d dt=%.4f sim_playing=%s " - "visualizer_count=%d requires_forward=%s", - self._visualizer_step_counter, - dt, - self.is_playing(), - len(self._visualizers), - self._should_forward_before_visualizer_update(), - ) - self.update_scene_data_provider() visualizers_to_remove = [] @@ -715,23 +728,6 @@ def update_visualizers(self, dt: float) -> None: viz.step(0.0) continue while viz.is_training_paused() and viz.is_running(): - if _VIS_DEBUG_ENABLED: - pause_signature = ( - bool(self.is_playing()), - bool(viz.is_running()), - bool(viz.is_training_paused()), - id(viz), - ) - if pause_signature != self._debug_last_pause_signature: - logger.warning( - "[VIS-DEBUG][SimulationContext.update_visualizers] training paused loop: " - "viz=%s sim_playing=%s viz_running=%s viz_training_paused=%s", - type(viz).__name__, - self.is_playing(), - viz.is_running(), - viz.is_training_paused(), - ) - self._debug_last_pause_signature = pause_signature viz.step(0.0) viz.step(dt) except Exception as exc: diff --git a/source/isaaclab/isaaclab/visualizers/base_visualizer.py b/source/isaaclab/isaaclab/visualizers/base_visualizer.py index 2480bc89bbaa..bf66ea2b43b9 100644 --- a/source/isaaclab/isaaclab/visualizers/base_visualizer.py +++ b/source/isaaclab/isaaclab/visualizers/base_visualizer.py @@ -187,6 +187,27 @@ def set_camera_view(self, eye: tuple, target: tuple) -> None: """ pass + def _resolve_cfg_camera_pose( + self, visualizer_name: str + ) -> tuple[tuple[float, float, float], tuple[float, float, float]] | None: + """Resolve camera pose from cfg fields, allowing opt-out via ``None``. + + Returns ``None`` when both cfg camera fields are ``None`` (keep backend + default camera) or when only one field is ``None`` (invalid partial pose). + """ + eye = getattr(self.cfg, "eye", None) + lookat = getattr(self.cfg, "lookat", None) + if eye is None and lookat is None: + return None + if eye is None or lookat is None: + logger.warning( + "[%s] eye/lookat must be both set or both None. " + "Keeping current camera pose.", + visualizer_name, + ) + return None + return eye, lookat + def _resolve_camera_pose_from_usd_path( self, usd_path: str ) -> tuple[tuple[float, float, float], tuple[float, float, float]] | None: diff --git a/source/isaaclab/isaaclab/visualizers/visualizer_cfg.py b/source/isaaclab/isaaclab/visualizers/visualizer_cfg.py index a96e3c04d2b5..4e3820a2bd9e 100644 --- a/source/isaaclab/isaaclab/visualizers/visualizer_cfg.py +++ b/source/isaaclab/isaaclab/visualizers/visualizer_cfg.py @@ -34,14 +34,22 @@ class VisualizerCfg: enable_live_plots: bool = True """Enable live plotting of data.""" - camera_position: tuple[float, float, float] = (8.0, 8.0, 3.0) - """Initial camera position (x, y, z) in world coordinates.""" + eye: tuple[float, float, float] | None = (8.0, 8.0, 3.0) + """Initial camera eye 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.""" + Set to ``None`` (with :attr:`lookat` also set to ``None``) to keep + the visualizer's default camera pose. + """ + + lookat: tuple[float, float, float] | None = (0.0, 0.0, 0.0) + """Initial camera look-at point (x, y, z) in world coordinates. + + Set to ``None`` (with :attr:`eye` also set to ``None``) to keep + the visualizer's default camera pose. + """ camera_source: Literal["cfg", "usd_path"] = "cfg" - """Camera source mode: 'cfg' uses camera_position/target, 'usd_path' follows a USD camera prim.""" + """Camera source mode: 'cfg' uses eye/lookat, 'usd_path' follows a USD camera prim.""" camera_usd_path: str = "/World/envs/env_0/Camera" """Absolute USD path to a camera prim when camera_source='usd_path'.""" diff --git a/source/isaaclab/test/envs/test_color_randomization.py b/source/isaaclab/test/envs/test_color_randomization.py index cee00ee90aa5..a7edda7036c1 100644 --- a/source/isaaclab/test/envs/test_color_randomization.py +++ b/source/isaaclab/test/envs/test_color_randomization.py @@ -126,8 +126,8 @@ class CartpoleEnvCfg(ManagerBasedEnvCfg): def __post_init__(self): """Post initialization.""" # viewer settings - self.viewer.position = [4.5, 0.0, 6.0] - self.viewer.target_position = [0.0, 0.0, 2.0] + self.viewer.eye = [4.5, 0.0, 6.0] + self.viewer.lookat = [0.0, 0.0, 2.0] # step settings self.decimation = 4 # env step every 4 sim steps: 200Hz / 4 = 50Hz # simulation settings diff --git a/source/isaaclab/test/envs/test_texture_randomization.py b/source/isaaclab/test/envs/test_texture_randomization.py index 256c9f2271ff..b5fe287c48ce 100644 --- a/source/isaaclab/test/envs/test_texture_randomization.py +++ b/source/isaaclab/test/envs/test_texture_randomization.py @@ -172,8 +172,8 @@ class CartpoleEnvCfg(ManagerBasedEnvCfg): def __post_init__(self): """Post initialization.""" # viewer settings - self.viewer.position = [4.5, 0.0, 6.0] - self.viewer.target_position = [0.0, 0.0, 2.0] + self.viewer.eye = [4.5, 0.0, 6.0] + self.viewer.lookat = [0.0, 0.0, 2.0] # step settings self.decimation = 4 # env step every 4 sim steps: 200Hz / 4 = 50Hz # simulation settings diff --git a/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py b/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py index a6c01a4e837b..2298cbbb2d70 100644 --- a/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py +++ b/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py @@ -42,7 +42,6 @@ __all__ = ["IsaacEvents", "PhysxManager"] logger = logging.getLogger(__name__) -_VIS_DEBUG_ENABLED = os.getenv("ISAACLAB_VIS_DEBUG", "0").lower() in {"1", "true", "yes", "on"} class IsaacEvents(Enum): @@ -176,8 +175,6 @@ class PhysxManager(PhysicsManager): _subscriptions: ClassVar[dict[str, Any]] = {} _fabric: ClassVar[Any] = None _update_fabric: ClassVar[Callable[[float, float], None] | None] = None - _debug_forward_counter: ClassVar[int] = 0 - _debug_last_forward_signature: ClassVar[tuple[bool, bool, bool] | None] = None _anim_recorder: ClassVar[AnimationRecorder | None] = None _callback_exception: ClassVar[Exception | None] = None @@ -247,29 +244,9 @@ def forward(cls) -> None: """Update articulation kinematics and fabric for rendering.""" sim = PhysicsManager._sim if cls._fabric is not None and cls._update_fabric is not None: - sim_is_playing = bool(sim is not None and sim.is_playing()) - timeline_playing = bool(cls._timeline is not None and cls._timeline.is_playing()) - has_view = bool(cls._view is not None) - did_update_kinematics = False - if has_view and sim_is_playing: + if cls._view is not None and sim is not None and sim.is_playing(): cls._view.update_articulations_kinematic() - did_update_kinematics = True cls._update_fabric(0.0, 0.0) - cls._debug_forward_counter += 1 - if _VIS_DEBUG_ENABLED: - signature = (sim_is_playing, has_view, did_update_kinematics) - if cls._debug_last_forward_signature != signature or (cls._debug_forward_counter % 120 == 0): - logger.warning( - "[VIS-DEBUG][PhysxManager.forward] count=%d sim_playing=%s timeline_playing=%s has_view=%s " - "updated_kinematics=%s updated_fabric=%s", - cls._debug_forward_counter, - sim_is_playing, - timeline_playing, - has_view, - did_update_kinematics, - True, - ) - cls._debug_last_forward_signature = signature @classmethod def step(cls) -> None: diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/classic/cartpole/cartpole_camera_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/classic/cartpole/cartpole_camera_env_cfg.py index be0c9aa99869..dfccd3d36890 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/classic/cartpole/cartpole_camera_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/classic/cartpole/cartpole_camera_env_cfg.py @@ -142,8 +142,8 @@ def __post_init__(self): # remove ground as it obstructs the camera self.scene.ground = None # viewer settings - self.viewer.position = (7.0, 0.0, 2.5) - self.viewer.target_position = (0.0, 0.0, 2.5) + self.viewer.eye = (7.0, 0.0, 2.5) + self.viewer.lookat = (0.0, 0.0, 2.5) @configclass @@ -158,8 +158,8 @@ def __post_init__(self): # remove ground as it obstructs the camera self.scene.ground = None # viewer settings - self.viewer.position = (7.0, 0.0, 2.5) - self.viewer.target_position = (0.0, 0.0, 2.5) + self.viewer.eye = (7.0, 0.0, 2.5) + self.viewer.lookat = (0.0, 0.0, 2.5) @configclass 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 78010c67024b..660be6136e22 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 @@ -202,7 +202,7 @@ def __post_init__(self) -> None: self.decimation = 2 self.episode_length_s = 5 # viewer settings - self.viewer.position = (8.0, 0.0, 5.0) + self.viewer.eye = (8.0, 0.0, 5.0) # simulation settings self.sim.dt = 1 / 120 self.sim.render_interval = self.decimation 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 31b4e66bd4f6..2714b2cd40a2 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 @@ -335,6 +335,6 @@ def __post_init__(self): # general settings self.decimation = 1 self.episode_length_s = 8.0 - self.viewer.position = (-2.0, 2.0, 2.0) - self.viewer.target_position = (0.8, 0.0, 0.5) + self.viewer.eye = (-2.0, 2.0, 2.0) + self.viewer.lookat = (0.8, 0.0, 0.5) # simulation settings are defined in CabinetSimCfg (dt/physics vary per backend) 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 771d5c2b597c..8adcddcb8b0f 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,8 +275,8 @@ def __post_init__(self): # general settings self.decimation = 1 self.episode_length_s = 8.0 - self.viewer.position = (-2.0, 2.0, 2.0) - self.viewer.target_position = (0.8, 0.0, 0.5) + 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.render_interval = self.decimation diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/deploy/gear_assembly/gear_assembly_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/deploy/gear_assembly/gear_assembly_env_cfg.py index 32be1cf8fd2f..6a3fc7f080f4 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/deploy/gear_assembly/gear_assembly_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/deploy/gear_assembly/gear_assembly_env_cfg.py @@ -312,7 +312,7 @@ def __post_init__(self): """Post initialization.""" # general settings self.episode_length_s = 6.66 - self.viewer.position = (3.5, 3.5, 3.5) + self.viewer.eye = (3.5, 3.5, 3.5) # simulation settings self.decimation = 4 self.sim.render_interval = self.decimation 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 d26ff7555cd1..018ef3a49c9c 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 @@ -210,6 +210,6 @@ def __post_init__(self): self.decimation = 2 self.sim.render_interval = self.decimation self.episode_length_s = 12.0 - self.viewer.position = (3.5, 3.5, 3.5) + self.viewer.eye = (3.5, 3.5, 3.5) # simulation settings self.sim.dt = 1.0 / 120.0 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 96a802ec8eb2..891d166c8e1a 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 @@ -345,4 +345,4 @@ def __post_init__(self): self.sim.dt = 1.0 / 120.0 self.sim.render_interval = self.decimation # change viewer settings - self.viewer.position = (2.0, 2.0, 2.0) + self.viewer.eye = (2.0, 2.0, 2.0) 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 66cae30fc3a0..4d70b1571a5f 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 @@ -202,8 +202,8 @@ def __post_init__(self): ) # set viewer to see the whole scene - self.viewer.position = [1.5, -1.0, 1.5] - self.viewer.target_position = [0.5, 0.0, 0.0] + self.viewer.eye = [1.5, -1.0, 1.5] + self.viewer.lookat = [0.5, 0.0, 0.0] """ 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 a667d3cb176f..f111cb41cd20 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 @@ -330,6 +330,6 @@ def __post_init__(self): self.decimation = 2 self.sim.render_interval = self.decimation self.episode_length_s = 24.0 - self.viewer.position = (3.5, 3.5, 3.5) + self.viewer.eye = (3.5, 3.5, 3.5) # simulation settings self.sim.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 c375da063a5f..efde276b7dc6 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 @@ -243,6 +243,6 @@ def __post_init__(self): self.decimation = 2 self.sim.render_interval = self.decimation self.episode_length_s = 12.0 - self.viewer.position = (3.5, 3.5, 3.5) + self.viewer.eye = (3.5, 3.5, 3.5) # simulation settings self.sim.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 1c02e939f44a..3bf9cc0443fc 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 @@ -252,7 +252,7 @@ def __post_init__(self): self.decimation = 2 self.sim.render_interval = self.decimation self.episode_length_s = 12.0 - self.viewer.position = (3.5, 3.5, 3.5) + self.viewer.eye = (3.5, 3.5, 3.5) # simulation settings self.sim.dt = 1.0 / 60.0 self.sim.physics = ReachPhysicsCfg() diff --git a/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualizer.py b/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualizer.py index e594dd541efc..ec3449ea4876 100644 --- a/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualizer.py +++ b/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualizer.py @@ -9,7 +9,6 @@ import asyncio import logging -import os from typing import TYPE_CHECKING from pxr import UsdGeom @@ -19,7 +18,6 @@ from .kit_visualizer_cfg import KitVisualizerCfg logger = logging.getLogger(__name__) -_VIS_DEBUG_ENABLED = os.getenv("ISAACLAB_VIS_DEBUG", "0").lower() in {"1", "true", "yes", "on"} if TYPE_CHECKING: from isaaclab.physics import BaseSceneDataProvider @@ -48,9 +46,6 @@ def __init__(self, cfg: KitVisualizerCfg): # user-switching the GUI viewport to a sensor camera does not corrupt the sensor's prim. self._controlled_camera_path: str | None = None self._runtime_headless = bool(cfg.headless) - self._debug_last_step_state: tuple[bool, bool, bool | None] | None = None - self._debug_period_steps = 120 - self._last_timeline_playing: bool | None = None # ---- Lifecycle ------------------------------------------------------------------------ @@ -86,8 +81,8 @@ def initialize(self, scene_data_provider: BaseSceneDataProvider) -> None: logger=logger, title="KitVisualizer Configuration", rows=[ - ("camera_position", self.cfg.camera_position), - ("camera_target", self.cfg.camera_target), + ("eye", self.cfg.eye), + ("lookat", self.cfg.lookat), ("camera_source", self.cfg.camera_source), ("num_visualized_envs", num_visualized_envs), ("create_viewport", self.cfg.create_viewport), @@ -108,53 +103,11 @@ def step(self, dt: float) -> None: self._sim_time += dt self._step_counter += 1 try: - import carb.settings import omni.kit.app - import omni.timeline app = omni.kit.app.get_app() if app is not None and app.is_running(): - # Pump Kit/UI events only; SimulationContext owns physics stepping. - settings = carb.settings.get_settings() - play_simulations_path = "/app/player/playSimulations" - previous_play_simulations = None if settings is None else settings.get(play_simulations_path) - timeline = omni.timeline.get_timeline_interface() - timeline_playing = bool(timeline is not None and timeline.is_playing()) - timeline_stopped = bool(timeline is not None and timeline.is_stopped()) - timeline_pause_state = (not timeline_playing) and (not timeline_stopped) - should_temporarily_pause = bool(previous_play_simulations) - did_app_update = False - try: - # Prevent app.update() from stepping physics. SimulationContext owns stepping. - if should_temporarily_pause and settings is not None: - settings.set_bool(play_simulations_path, False) - app.update() - did_app_update = True - finally: - if should_temporarily_pause and settings is not None: - settings.set_bool(play_simulations_path, True) - - if _VIS_DEBUG_ENABLED: - state = (timeline_playing, timeline_stopped, previous_play_simulations) - if ( - self._debug_last_step_state != state - or (self._step_counter % self._debug_period_steps == 0) - or not did_app_update - ): - logger.warning( - "[VIS-DEBUG][KitVisualizer.step] step=%d dt=%.4f timeline_playing=%s timeline_stopped=%s " - "playSim_before=%s playSim_target=%s timeline_paused=%s app_update=%s", - self._step_counter, - dt, - timeline_playing, - timeline_stopped, - previous_play_simulations, - bool(not should_temporarily_pause), - timeline_pause_state, - did_app_update, - ) - self._debug_last_step_state = state - self._last_timeline_playing = timeline_playing + app.update() except (ImportError, AttributeError) as exc: logger.debug("[KitVisualizer] App update skipped: %s", exc) @@ -270,6 +223,8 @@ def _setup_viewport(self, usd_stage) -> None: # In headless mode we keep the visualizer active but skip viewport/window setup. self._viewport_window = None self._viewport_api = None + self._controlled_camera_path = "/OmniverseKit_Persp" + self._apply_cfg_camera_pose_if_configured() return if self.cfg.create_viewport and self.cfg.viewport_name: @@ -310,9 +265,9 @@ def _setup_viewport(self, usd_stage) -> None: "[KitVisualizer] camera_usd_path '%s' not found; using configured camera.", self.cfg.camera_usd_path, ) - self._set_viewport_camera(self.cfg.camera_position, self.cfg.camera_target) + self._apply_cfg_camera_pose_if_configured() else: - self._set_viewport_camera(self.cfg.camera_position, self.cfg.camera_target) + self._apply_cfg_camera_pose_if_configured() async def _dock_viewport_async(self, viewport_name: str, dock_position) -> None: """Dock a created viewport window relative to main viewport.""" @@ -361,8 +316,6 @@ def _set_viewport_camera(self, position: tuple[float, float, float], target: tup """Apply eye/target camera view to the active viewport.""" import isaacsim.core.utils.viewports as isaacsim_viewports - if self._viewport_api is None: - return # Use the camera path pinned at initialization. This prevents user-switching the GUI # viewport to a sensor camera from corrupting the sensor's USD prim transform. camera_path = self._controlled_camera_path @@ -370,10 +323,26 @@ def _set_viewport_camera(self, position: tuple[float, float, float], target: tup camera_path = self._viewport_api.get_active_camera() if self._viewport_api else None if not camera_path: camera_path = "/OmniverseKit_Persp" + kwargs = {"eye": list(position), "target": list(target), "camera_prim_path": camera_path} + if self._viewport_api is not None: + kwargs["viewport_api"] = self._viewport_api + isaacsim_viewports.set_camera_view(**kwargs) - isaacsim_viewports.set_camera_view( - eye=list(position), target=list(target), camera_prim_path=camera_path, viewport_api=self._viewport_api - ) + def _apply_cfg_camera_pose_if_configured(self) -> None: + """Apply configured camera pose if both position and target are provided. + + When either field is ``None``, keep the current/default perspective + camera transform unchanged. + """ + if self.cfg.eye is None and self.cfg.lookat is None: + return + if self.cfg.eye is None or self.cfg.lookat is None: + logger.warning( + "[KitVisualizer] eye/lookat must be both set or both None. " + "Keeping current camera pose." + ) + return + self._set_viewport_camera(self.cfg.eye, self.cfg.lookat) def _set_active_camera_path(self, camera_path: str) -> bool: """Set active camera path for viewport if the prim exists. diff --git a/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualizer_cfg.py b/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualizer_cfg.py index 88112a6f20b4..41e0f734eec4 100644 --- a/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualizer_cfg.py +++ b/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualizer_cfg.py @@ -16,6 +16,20 @@ class KitVisualizerCfg(VisualizerCfg): visualizer_type: str = "kit" """Type identifier for Kit visualizer.""" + eye: tuple[float, float, float] | None = (8.0, 8.0, 3.0) + """Initial camera eye override. + + If set to ``None`` (with :attr:`lookat` also set to ``None``), the + visualizer keeps the current/default perspective camera pose. + """ + + lookat: tuple[float, float, float] | None = (0.0, 0.0, 0.0) + """Initial camera look-at override. + + If set to ``None`` (with :attr:`eye` also set to ``None``), the + visualizer keeps the current/default perspective camera pose. + """ + viewport_name: str | None = "Visualizer Viewport" """Viewport name to use. If None, uses active viewport.""" diff --git a/source/isaaclab_visualizers/isaaclab_visualizers/newton/newton_visualizer.py b/source/isaaclab_visualizers/isaaclab_visualizers/newton/newton_visualizer.py index 70d44d1956f7..7c16a8af73a4 100644 --- a/source/isaaclab_visualizers/isaaclab_visualizers/newton/newton_visualizer.py +++ b/source/isaaclab_visualizers/isaaclab_visualizers/newton/newton_visualizer.py @@ -308,7 +308,9 @@ def initialize(self, scene_data_provider: BaseSceneDataProvider) -> None: max_worlds = self.cfg.max_worlds self._viewer.set_model(self._model, max_worlds=max_worlds) self._viewer.set_world_offsets((0.0, 0.0, 0.0)) - self._apply_camera_pose(self._resolve_initial_camera_pose()) + initial_pose = self._resolve_initial_camera_pose() + if initial_pose is not None: + self._apply_camera_pose(initial_pose) self._viewer.up_axis = 2 # Z-up self._viewer.scaling = 1.0 @@ -334,12 +336,12 @@ def initialize(self, scene_data_provider: BaseSceneDataProvider) -> None: title="NewtonVisualizer Configuration", rows=[ ( - "camera_position", + "eye", tuple(float(x) for x in self._viewer.camera.pos) if self._viewer is not None - else self.cfg.camera_position, + else self.cfg.eye, ), - ("camera_target", self._last_camera_pose[1] if self._last_camera_pose else self.cfg.camera_target), + ("lookat", self._last_camera_pose[1] if self._last_camera_pose else self.cfg.lookat), ("camera_source", self.cfg.camera_source), ("num_visualized_envs", num_visualized_envs), ("headless", self.cfg.headless), @@ -423,11 +425,11 @@ def is_running(self) -> bool: return False return self._viewer.is_running() - def _resolve_initial_camera_pose(self) -> tuple[tuple[float, float, float], tuple[float, float, float]]: + def _resolve_initial_camera_pose(self) -> tuple[tuple[float, float, float], tuple[float, float, float]] | None: """Resolve initial camera pose from config or USD camera path. Returns: - Camera eye and target tuples. + Camera eye and target tuples, or ``None`` to keep viewer defaults. """ if self.cfg.camera_source == "usd_path": pose = self._resolve_camera_pose_from_usd_path(self.cfg.camera_usd_path) @@ -437,7 +439,7 @@ def _resolve_initial_camera_pose(self) -> tuple[tuple[float, float, float], tupl "[NewtonVisualizer] camera_usd_path '%s' not found; using configured camera.", self.cfg.camera_usd_path, ) - return self.cfg.camera_position, self.cfg.camera_target + return self._resolve_cfg_camera_pose("NewtonVisualizer") def _apply_camera_pose(self, pose: tuple[tuple[float, float, float], tuple[float, float, float]]) -> None: """Apply camera eye/target pose to the Newton viewer. diff --git a/source/isaaclab_visualizers/isaaclab_visualizers/rerun/rerun_visualizer.py b/source/isaaclab_visualizers/isaaclab_visualizers/rerun/rerun_visualizer.py index ab2ed723223f..21a02baf656e 100644 --- a/source/isaaclab_visualizers/isaaclab_visualizers/rerun/rerun_visualizer.py +++ b/source/isaaclab_visualizers/isaaclab_visualizers/rerun/rerun_visualizer.py @@ -188,7 +188,9 @@ def initialize(self, scene_data_provider: BaseSceneDataProvider) -> None: self._viewer.set_model(self._model, max_worlds=self.cfg.max_worlds) # Preserve simulation world positions (env_spacing) rather than adding viewer-side offsets. self._viewer.set_world_offsets((0.0, 0.0, 0.0)) - self._apply_camera_pose(self._resolve_initial_camera_pose()) + initial_pose = self._resolve_initial_camera_pose() + if initial_pose is not None: + self._apply_camera_pose(initial_pose) self._viewer.up_axis = 2 self._viewer.scaling = 1.0 self._viewer._paused = False @@ -198,8 +200,8 @@ def initialize(self, scene_data_provider: BaseSceneDataProvider) -> None: logger=logger, title="RerunVisualizer Configuration", rows=[ - ("camera_position", self.cfg.camera_position), - ("camera_target", self.cfg.camera_target), + ("eye", self.cfg.eye), + ("lookat", self.cfg.lookat), ("camera_source", self.cfg.camera_source), ("num_visualized_envs", num_visualized_envs), ("endpoint", f"http://{viewer_host}:{web_port}"), @@ -273,13 +275,13 @@ def is_running(self) -> bool: return False return self._viewer.is_running() - def _resolve_initial_camera_pose(self) -> tuple[tuple[float, float, float], tuple[float, float, float]]: + def _resolve_initial_camera_pose(self) -> tuple[tuple[float, float, float], tuple[float, float, float]] | None: """Resolve initial camera pose from config or USD camera path.""" if self.cfg.camera_source == "usd_path": pose = self._resolve_camera_pose_from_usd_path(self.cfg.camera_usd_path) if pose is not None: return pose - return self.cfg.camera_position, self.cfg.camera_target + return self._resolve_cfg_camera_pose("RerunVisualizer") def _apply_camera_pose(self, pose: tuple[tuple[float, float, float], tuple[float, float, float]]) -> None: """Apply camera pose to rerun's 3D view controls. diff --git a/source/isaaclab_visualizers/isaaclab_visualizers/viser/viser_visualizer.py b/source/isaaclab_visualizers/isaaclab_visualizers/viser/viser_visualizer.py index c20bfcd85a9f..d2cf60fd2c66 100644 --- a/source/isaaclab_visualizers/isaaclab_visualizers/viser/viser_visualizer.py +++ b/source/isaaclab_visualizers/isaaclab_visualizers/viser/viser_visualizer.py @@ -162,8 +162,8 @@ def initialize(self, scene_data_provider: BaseSceneDataProvider) -> None: logger=logger, title="ViserVisualizer Configuration", rows=[ - ("camera_position", self.cfg.camera_position), - ("camera_target", self.cfg.camera_target), + ("eye", self.cfg.eye), + ("lookat", self.cfg.lookat), ("camera_source", self.cfg.camera_source), ("num_visualized_envs", num_visualized_envs), ("port", self.cfg.port), @@ -259,7 +259,9 @@ def _create_viewer(self, record_to_viser: str | None, metadata: dict | None = No self._viewer.set_world_offsets((0.0, 0.0, 0.0)) if self.cfg.open_browser: _open_viser_web_viewer(self.cfg.port) - self._set_viser_camera_view(self._resolve_initial_camera_pose()) + initial_pose = self._resolve_initial_camera_pose() + if initial_pose is not None: + self._set_viser_camera_view(initial_pose) self._sim_time = 0.0 def _close_viewer(self, finalize_viser: bool = False) -> None: @@ -275,7 +277,7 @@ def _close_viewer(self, finalize_viser: bool = False) -> None: logger.warning("[ViserVisualizer] Recording file not found: %s", self._active_record_path) self._viewer = None - def _resolve_initial_camera_pose(self) -> tuple[tuple[float, float, float], tuple[float, float, float]]: + def _resolve_initial_camera_pose(self) -> tuple[tuple[float, float, float], tuple[float, float, float]] | None: """Resolve initial camera pose from config or USD camera path.""" if self.cfg.camera_source == "usd_path": pose = self._resolve_camera_pose_from_usd_path(self.cfg.camera_usd_path) @@ -285,7 +287,7 @@ def _resolve_initial_camera_pose(self) -> tuple[tuple[float, float, float], tupl "[ViserVisualizer] camera_usd_path '%s' not found; using configured camera.", self.cfg.camera_usd_path, ) - return self.cfg.camera_position, self.cfg.camera_target + return self._resolve_cfg_camera_pose("ViserVisualizer") def _try_apply_viser_camera_view(self, pose: tuple[tuple[float, float, float], tuple[float, float, float]]) -> bool: """Try applying camera pose to active viser clients. From 408c3125fb4c375b6f51c208cd010b2c58864cdd Mon Sep 17 00:00:00 2001 From: Matthew Trepte Date: Thu, 2 Apr 2026 01:53:52 +0000 Subject: [PATCH 09/11] resolve overlapping beahvior in viewrcfg and visualizercfg --- source/isaaclab/isaaclab/envs/common.py | 3 +- .../isaaclab/isaaclab/envs/direct_marl_env.py | 2 +- .../isaaclab/isaaclab/envs/direct_rl_env.py | 2 +- .../isaaclab/envs/manager_based_env.py | 2 +- .../envs/mdp/commands/velocity_command.py | 1 + .../envs/ui/viewport_camera_controller.py | 4 +- .../isaaclab/sim/simulation_context.py | 19 ++++++ .../isaaclab/visualizers/base_visualizer.py | 22 ++----- .../isaaclab/visualizers/visualizer_cfg.py | 24 +++----- .../kit/kit_visualizer.py | 58 ++++++++++--------- .../kit/kit_visualizer_cfg.py | 26 ++++----- .../newton/newton_visualizer.py | 27 ++++----- .../rerun/rerun_visualizer.py | 19 +++--- .../viser/viser_visualizer.py | 21 ++++--- 14 files changed, 114 insertions(+), 116 deletions(-) diff --git a/source/isaaclab/isaaclab/envs/common.py b/source/isaaclab/isaaclab/envs/common.py index cf1206908c8f..1af713a0eed0 100644 --- a/source/isaaclab/isaaclab/envs/common.py +++ b/source/isaaclab/isaaclab/envs/common.py @@ -21,7 +21,7 @@ class ViewerCfg: """Configuration of the scene viewport camera.""" - eye: tuple[float, float, float] = (7.5, 7.5, 117.5) + eye: tuple[float, float, float] = (7.5, 7.5, 7.5) """Initial camera position (in m). Default is (7.5, 7.5, 7.5).""" lookat: tuple[float, float, float] = (0.0, 0.0, 0.0) @@ -67,6 +67,7 @@ class ViewerCfg: This quantity is only effective if :attr:`origin` is set to "asset_body". """ + ## # Types. ## diff --git a/source/isaaclab/isaaclab/envs/direct_marl_env.py b/source/isaaclab/isaaclab/envs/direct_marl_env.py index 3d028a2a7ba9..31df5ee4155d 100644 --- a/source/isaaclab/isaaclab/envs/direct_marl_env.py +++ b/source/isaaclab/isaaclab/envs/direct_marl_env.py @@ -151,7 +151,7 @@ def _init_sim(self, render_mode: str | None = None, **kwargs): # FIXME: This needs to be fixed in the future when we unify the UI functionalities even for # non-rendering modes. # Initialize when GUI is available OR when visualizers are active (headless rendering) - # Visualizers support camera updates via sim.set_camera_view() which forwards to all active visualizers + # ViewerCfg camera updates are applied through renderer camera control. has_visualizers = bool(self.sim.get_setting("/isaaclab/visualizer/types")) or bool( self.sim.get_setting("/isaaclab/video/auto_start_kit") ) diff --git a/source/isaaclab/isaaclab/envs/direct_rl_env.py b/source/isaaclab/isaaclab/envs/direct_rl_env.py index 6ba9fbae4e58..d2a220f1d0bd 100644 --- a/source/isaaclab/isaaclab/envs/direct_rl_env.py +++ b/source/isaaclab/isaaclab/envs/direct_rl_env.py @@ -156,7 +156,7 @@ def _init_sim(self, render_mode: str | None = None, **kwargs): # FIXME: This needs to be fixed in the future when we unify the UI functionalities even for # non-rendering modes. # Initialize when GUI is available OR when visualizers are active (headless rendering) - # Visualizers support camera updates via sim.set_camera_view() which forwards to all active visualizers + # ViewerCfg camera updates are applied through renderer camera control. has_visualizers = bool(self.sim.get_setting("/isaaclab/visualizer/types")) or bool( self.sim.get_setting("/isaaclab/video/auto_start_kit") ) diff --git a/source/isaaclab/isaaclab/envs/manager_based_env.py b/source/isaaclab/isaaclab/envs/manager_based_env.py index a8d201b3a966..05b267df8a50 100644 --- a/source/isaaclab/isaaclab/envs/manager_based_env.py +++ b/source/isaaclab/isaaclab/envs/manager_based_env.py @@ -166,7 +166,7 @@ def _init_sim(self): # FIXME: This needs to be fixed in the future when we unify the UI functionalities even for # non-rendering modes. # Initialize when GUI is available OR when visualizers are active (headless rendering) - # Visualizers support camera updates via sim.set_camera_view() which forwards to all active visualizers + # ViewerCfg camera updates are applied through renderer camera control. has_visualizers = bool(self.sim.get_setting("/isaaclab/visualizer/types")) or bool( self.sim.get_setting("/isaaclab/video/auto_start_kit") ) diff --git a/source/isaaclab/isaaclab/envs/mdp/commands/velocity_command.py b/source/isaaclab/isaaclab/envs/mdp/commands/velocity_command.py index efd7278d2f1f..eadc89af3af9 100644 --- a/source/isaaclab/isaaclab/envs/mdp/commands/velocity_command.py +++ b/source/isaaclab/isaaclab/envs/mdp/commands/velocity_command.py @@ -223,6 +223,7 @@ def _resolve_xy_velocity_to_arrow(self, xy_velocity: torch.Tensor) -> tuple[torc return arrow_scale, arrow_quat + class NormalVelocityCommand(UniformVelocityCommand): """Command generator that generates a velocity command in SE(2) from a normal distribution. diff --git a/source/isaaclab/isaaclab/envs/ui/viewport_camera_controller.py b/source/isaaclab/isaaclab/envs/ui/viewport_camera_controller.py index 4126d7b74735..6a89c482accc 100644 --- a/source/isaaclab/isaaclab/envs/ui/viewport_camera_controller.py +++ b/source/isaaclab/isaaclab/envs/ui/viewport_camera_controller.py @@ -218,8 +218,8 @@ def update_view_location(self, eye: Sequence[float] | None = None, lookat: Seque cam_eye = viewer_origin + self.default_cam_eye cam_target = viewer_origin + self.default_cam_lookat - # set the camera view - self._env.sim.set_camera_view(eye=cam_eye, target=cam_target) + # set the renderer viewport camera view (does not broadcast to visualizers) + self._env.sim.set_renderer_camera_view(eye=cam_eye, target=cam_target, camera_prim_path=self.cfg.cam_prim_path) """ Private Functions diff --git a/source/isaaclab/isaaclab/sim/simulation_context.py b/source/isaaclab/isaaclab/sim/simulation_context.py index 8b7ffbd74367..30cd1410e68a 100644 --- a/source/isaaclab/isaaclab/sim/simulation_context.py +++ b/source/isaaclab/isaaclab/sim/simulation_context.py @@ -659,6 +659,25 @@ def set_camera_view(self, eye: tuple, target: tuple) -> None: for viz in self._visualizers: viz.set_camera_view(eye, target) + def set_renderer_camera_view( + self, + eye: tuple[float, float, float] | list[float], + target: tuple[float, float, float] | list[float], + camera_prim_path: str = "/OmniverseKit_Persp", + ) -> None: + """Set camera view for renderer/viewport camera only. + + This does not broadcast to visualizers. + """ + try: + import isaacsim.core.utils.viewports as isaacsim_viewports + + isaacsim_viewports.set_camera_view( + eye=list(eye), target=list(target), camera_prim_path=str(camera_prim_path) + ) + except Exception as exc: + logger.debug("[SimulationContext] Renderer camera update skipped: %s", exc) + def forward(self) -> None: """Update kinematics without stepping physics.""" self.physics_manager.forward() diff --git a/source/isaaclab/isaaclab/visualizers/base_visualizer.py b/source/isaaclab/isaaclab/visualizers/base_visualizer.py index bf66ea2b43b9..159b50eb7813 100644 --- a/source/isaaclab/isaaclab/visualizers/base_visualizer.py +++ b/source/isaaclab/isaaclab/visualizers/base_visualizer.py @@ -189,23 +189,11 @@ def set_camera_view(self, eye: tuple, target: tuple) -> None: def _resolve_cfg_camera_pose( self, visualizer_name: str - ) -> tuple[tuple[float, float, float], tuple[float, float, float]] | None: - """Resolve camera pose from cfg fields, allowing opt-out via ``None``. - - Returns ``None`` when both cfg camera fields are ``None`` (keep backend - default camera) or when only one field is ``None`` (invalid partial pose). - """ - eye = getattr(self.cfg, "eye", None) - lookat = getattr(self.cfg, "lookat", None) - if eye is None and lookat is None: - return None - if eye is None or lookat is None: - logger.warning( - "[%s] eye/lookat must be both set or both None. " - "Keeping current camera pose.", - visualizer_name, - ) - return None + ) -> tuple[tuple[float, float, float], tuple[float, float, float]]: + """Resolve camera pose from cfg eye/lookat fields.""" + del visualizer_name + eye = tuple(float(v) for v in getattr(self.cfg, "eye")) + lookat = tuple(float(v) for v in getattr(self.cfg, "lookat")) return eye, lookat def _resolve_camera_pose_from_usd_path( diff --git a/source/isaaclab/isaaclab/visualizers/visualizer_cfg.py b/source/isaaclab/isaaclab/visualizers/visualizer_cfg.py index 4e3820a2bd9e..0bd362e4ccd9 100644 --- a/source/isaaclab/isaaclab/visualizers/visualizer_cfg.py +++ b/source/isaaclab/isaaclab/visualizers/visualizer_cfg.py @@ -34,25 +34,17 @@ class VisualizerCfg: enable_live_plots: bool = True """Enable live plotting of data.""" - eye: tuple[float, float, float] | None = (8.0, 8.0, 3.0) - """Initial camera eye position (x, y, z) in world coordinates. + eye: tuple[float, float, float] = (8.0, 8.0, 3.0) + """Initial camera eye position (x, y, z) in world coordinates.""" - Set to ``None`` (with :attr:`lookat` also set to ``None``) to keep - the visualizer's default camera pose. - """ - - lookat: tuple[float, float, float] | None = (0.0, 0.0, 0.0) - """Initial camera look-at point (x, y, z) in world coordinates. - - Set to ``None`` (with :attr:`eye` also set to ``None``) to keep - the visualizer's default camera pose. - """ + lookat: tuple[float, float, float] = (0.0, 0.0, 0.0) + """Initial camera look-at point (x, y, z) in world coordinates.""" - camera_source: Literal["cfg", "usd_path"] = "cfg" - """Camera source mode: 'cfg' uses eye/lookat, 'usd_path' follows a USD camera prim.""" + cam_source: Literal["cfg", "prim_path"] = "cfg" + """Camera source mode: 'cfg' uses eye/lookat, 'prim_path' follows a camera prim.""" - camera_usd_path: str = "/World/envs/env_0/Camera" - """Absolute USD path to a camera prim when camera_source='usd_path'.""" + cam_prim_path: str = "/World/envs/env_0/Camera" + """Absolute USD path to a camera prim when cam_source='prim_path'.""" env_filter_mode: Literal["none", "env_ids", "random_n"] = "none" """Env filter mode: 'none', 'env_ids', or 'random_n'.""" diff --git a/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualizer.py b/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualizer.py index ec3449ea4876..8593857ae054 100644 --- a/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualizer.py +++ b/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualizer.py @@ -83,7 +83,9 @@ def initialize(self, scene_data_provider: BaseSceneDataProvider) -> None: rows=[ ("eye", self.cfg.eye), ("lookat", self.cfg.lookat), - ("camera_source", self.cfg.camera_source), + ("cam_source", self.cfg.cam_source), + ("visualizer_camera_prim_path", self.cfg.visualizer_camera_prim_path), + ("enable_visualizer_cam", self.cfg.enable_visualizer_cam), ("num_visualized_envs", num_visualized_envs), ("create_viewport", self.cfg.create_viewport), ("headless", self._runtime_headless), @@ -181,6 +183,9 @@ def set_camera_view( if not self._is_initialized: logger.debug("[KitVisualizer] set_camera_view() ignored because visualizer is not initialized.") return + if not self.cfg.enable_visualizer_cam: + logger.debug("[KitVisualizer] set_camera_view() ignored because enable_visualizer_cam=False.") + return self._set_viewport_camera(tuple(eye), tuple(target)) # ---- Viewport + camera ---------------------------------------------------------------- @@ -223,11 +228,17 @@ def _setup_viewport(self, usd_stage) -> None: # In headless mode we keep the visualizer active but skip viewport/window setup. self._viewport_window = None self._viewport_api = None - self._controlled_camera_path = "/OmniverseKit_Persp" + self._controlled_camera_path = "/OmniverseKit_Persp" if self.cfg.enable_visualizer_cam else None + if not self.cfg.enable_visualizer_cam: + return self._apply_cfg_camera_pose_if_configured() return - if self.cfg.create_viewport and self.cfg.viewport_name: + if self.cfg.create_viewport: + if not self.cfg.viewport_name.strip(): + raise RuntimeError( + "[KitVisualizer] viewport_name must be a non-empty string when create_viewport=True." + ) dock_position_name = self.cfg.dock_position.upper() dock_position_map = { "LEFT": DockPosition.LEFT, @@ -247,7 +258,6 @@ def _setup_viewport(self, usd_stage) -> None: ) asyncio.ensure_future(self._dock_viewport_async(self.cfg.viewport_name, dock_pos)) - self._create_and_assign_camera(usd_stage) else: self._viewport_window = vp_utils.get_active_viewport_window() @@ -256,16 +266,18 @@ def _setup_viewport(self, usd_stage) -> None: self._viewport_api = None return self._viewport_api = self._viewport_window.viewport_api - # Pin the camera path we will write to, using the active camera at init time. - # This must happen before any _set_viewport_camera() call so the path is known. - self._controlled_camera_path = self._viewport_api.get_active_camera() or "/OmniverseKit_Persp" - if self.cfg.camera_source == "usd_path": - if not self._set_active_camera_path(self.cfg.camera_usd_path): - logger.warning( - "[KitVisualizer] camera_usd_path '%s' not found; using configured camera.", - self.cfg.camera_usd_path, + if not self.cfg.enable_visualizer_cam: + self._controlled_camera_path = None + return + # Always create/use a dedicated visualizer-controlled camera so we never mutate + # existing viewport cameras (e.g. /OmniverseKit_Persp or sensor cameras). + self._create_and_assign_camera(usd_stage) + if self.cfg.cam_source == "prim_path": + if not self._set_active_camera_path(self.cfg.cam_prim_path): + raise RuntimeError( + "[KitVisualizer] cam_source='prim_path' requires a valid cam_prim_path. " + f"Camera prim not found: '{self.cfg.cam_prim_path}'." ) - self._apply_cfg_camera_pose_if_configured() else: self._apply_cfg_camera_pose_if_configured() @@ -301,8 +313,10 @@ async def _dock_viewport_async(self, viewport_name: str, dock_position) -> None: viewport_window.focus() def _create_and_assign_camera(self, usd_stage) -> None: - """Create viewport camera prim (if needed) and set it active.""" - camera_path = f"/World/Cameras/{self.cfg.viewport_name}_Camera".replace(" ", "_") + """Create dedicated visualizer camera prim (if needed) and set it active.""" + camera_path = self.cfg.visualizer_camera_prim_path + if not camera_path: + raise RuntimeError("[KitVisualizer] visualizer_camera_prim_path must be a non-empty prim path.") camera_prim = usd_stage.GetPrimAtPath(camera_path) if not camera_prim.IsValid(): @@ -329,19 +343,7 @@ def _set_viewport_camera(self, position: tuple[float, float, float], target: tup isaacsim_viewports.set_camera_view(**kwargs) def _apply_cfg_camera_pose_if_configured(self) -> None: - """Apply configured camera pose if both position and target are provided. - - When either field is ``None``, keep the current/default perspective - camera transform unchanged. - """ - if self.cfg.eye is None and self.cfg.lookat is None: - return - if self.cfg.eye is None or self.cfg.lookat is None: - logger.warning( - "[KitVisualizer] eye/lookat must be both set or both None. " - "Keeping current camera pose." - ) - return + """Apply configured camera pose from eye/lookat.""" self._set_viewport_camera(self.cfg.eye, self.cfg.lookat) def _set_active_camera_path(self, camera_path: str) -> bool: diff --git a/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualizer_cfg.py b/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualizer_cfg.py index 41e0f734eec4..921dc42fc11c 100644 --- a/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualizer_cfg.py +++ b/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualizer_cfg.py @@ -16,25 +16,21 @@ class KitVisualizerCfg(VisualizerCfg): visualizer_type: str = "kit" """Type identifier for Kit visualizer.""" - eye: tuple[float, float, float] | None = (8.0, 8.0, 3.0) - """Initial camera eye override. + viewport_name: str = "Visualizer Viewport" + """Viewport name to use when :attr:`create_viewport` is True.""" - If set to ``None`` (with :attr:`lookat` also set to ``None``), the - visualizer keeps the current/default perspective camera pose. - """ - - lookat: tuple[float, float, float] | None = (0.0, 0.0, 0.0) - """Initial camera look-at override. + create_viewport: bool = False + """Create new viewport with specified name and camera pose.""" - If set to ``None`` (with :attr:`eye` also set to ``None``), the - visualizer keeps the current/default perspective camera pose. - """ + visualizer_camera_prim_path: str = "/World/Cameras/KitVisualizerCamera" + """Dedicated camera prim path controlled by the Kit visualizer.""" - viewport_name: str | None = "Visualizer Viewport" - """Viewport name to use. If None, uses active viewport.""" + enable_visualizer_cam: bool = False + """Whether the Kit visualizer should control/bind a dedicated viewport camera. - create_viewport: bool = False - """Create new viewport with specified name and camera pose.""" + If False, Kit does not create/switch camera prims and ignores visualizer camera control + updates (including eye/lookat and cam_source handling). + """ headless: bool = False """Run without creating viewport windows when supported by the app.""" diff --git a/source/isaaclab_visualizers/isaaclab_visualizers/newton/newton_visualizer.py b/source/isaaclab_visualizers/isaaclab_visualizers/newton/newton_visualizer.py index 7c16a8af73a4..ecc6f6d327d8 100644 --- a/source/isaaclab_visualizers/isaaclab_visualizers/newton/newton_visualizer.py +++ b/source/isaaclab_visualizers/isaaclab_visualizers/newton/newton_visualizer.py @@ -309,8 +309,7 @@ def initialize(self, scene_data_provider: BaseSceneDataProvider) -> None: self._viewer.set_model(self._model, max_worlds=max_worlds) self._viewer.set_world_offsets((0.0, 0.0, 0.0)) initial_pose = self._resolve_initial_camera_pose() - if initial_pose is not None: - self._apply_camera_pose(initial_pose) + self._apply_camera_pose(initial_pose) self._viewer.up_axis = 2 # Z-up self._viewer.scaling = 1.0 @@ -337,12 +336,10 @@ def initialize(self, scene_data_provider: BaseSceneDataProvider) -> None: rows=[ ( "eye", - tuple(float(x) for x in self._viewer.camera.pos) - if self._viewer is not None - else self.cfg.eye, + tuple(float(x) for x in self._viewer.camera.pos) if self._viewer is not None else self.cfg.eye, ), ("lookat", self._last_camera_pose[1] if self._last_camera_pose else self.cfg.lookat), - ("camera_source", self.cfg.camera_source), + ("cam_source", self.cfg.cam_source), ("num_visualized_envs", num_visualized_envs), ("headless", self.cfg.headless), ], @@ -366,7 +363,7 @@ def step(self, dt: float) -> None: self._state = self._scene_data_provider.get_newton_state(self._env_ids) return - if self.cfg.camera_source == "usd_path": + if self.cfg.cam_source == "prim_path": self._update_camera_from_usd_path() self._state = self._scene_data_provider.get_newton_state(self._env_ids) @@ -425,19 +422,19 @@ def is_running(self) -> bool: return False return self._viewer.is_running() - def _resolve_initial_camera_pose(self) -> tuple[tuple[float, float, float], tuple[float, float, float]] | None: + def _resolve_initial_camera_pose(self) -> tuple[tuple[float, float, float], tuple[float, float, float]]: """Resolve initial camera pose from config or USD camera path. Returns: - Camera eye and target tuples, or ``None`` to keep viewer defaults. + Camera eye and target tuples. """ - if self.cfg.camera_source == "usd_path": - pose = self._resolve_camera_pose_from_usd_path(self.cfg.camera_usd_path) + if self.cfg.cam_source == "prim_path": + pose = self._resolve_camera_pose_from_usd_path(self.cfg.cam_prim_path) if pose is not None: return pose - logger.warning( - "[NewtonVisualizer] camera_usd_path '%s' not found; using configured camera.", - self.cfg.camera_usd_path, + raise RuntimeError( + "[NewtonVisualizer] cam_source='prim_path' requires a resolvable camera prim path, " + f"but no camera pose was found for '{self.cfg.cam_prim_path}'." ) return self._resolve_cfg_camera_pose("NewtonVisualizer") @@ -463,7 +460,7 @@ def _apply_camera_pose(self, pose: tuple[tuple[float, float, float], tuple[float def _update_camera_from_usd_path(self) -> None: """Refresh camera pose from configured USD camera path when it changes.""" - pose = self._resolve_camera_pose_from_usd_path(self.cfg.camera_usd_path) + pose = self._resolve_camera_pose_from_usd_path(self.cfg.cam_prim_path) if pose is None: return if self._last_camera_pose == pose: diff --git a/source/isaaclab_visualizers/isaaclab_visualizers/rerun/rerun_visualizer.py b/source/isaaclab_visualizers/isaaclab_visualizers/rerun/rerun_visualizer.py index 21a02baf656e..531b067104c1 100644 --- a/source/isaaclab_visualizers/isaaclab_visualizers/rerun/rerun_visualizer.py +++ b/source/isaaclab_visualizers/isaaclab_visualizers/rerun/rerun_visualizer.py @@ -189,8 +189,7 @@ def initialize(self, scene_data_provider: BaseSceneDataProvider) -> None: # Preserve simulation world positions (env_spacing) rather than adding viewer-side offsets. self._viewer.set_world_offsets((0.0, 0.0, 0.0)) initial_pose = self._resolve_initial_camera_pose() - if initial_pose is not None: - self._apply_camera_pose(initial_pose) + self._apply_camera_pose(initial_pose) self._viewer.up_axis = 2 self._viewer.scaling = 1.0 self._viewer._paused = False @@ -202,7 +201,7 @@ def initialize(self, scene_data_provider: BaseSceneDataProvider) -> None: rows=[ ("eye", self.cfg.eye), ("lookat", self.cfg.lookat), - ("camera_source", self.cfg.camera_source), + ("cam_source", self.cfg.cam_source), ("num_visualized_envs", num_visualized_envs), ("endpoint", f"http://{viewer_host}:{web_port}"), ("viewer_url", viewer_url), @@ -229,7 +228,7 @@ def step(self, dt: float) -> None: self._sim_time += dt self._step_counter += 1 - if self.cfg.camera_source == "usd_path": + if self.cfg.cam_source == "prim_path": self._update_camera_from_usd_path() self._state = self._scene_data_provider.get_newton_state(self._env_ids) @@ -275,12 +274,16 @@ def is_running(self) -> bool: return False return self._viewer.is_running() - def _resolve_initial_camera_pose(self) -> tuple[tuple[float, float, float], tuple[float, float, float]] | None: + def _resolve_initial_camera_pose(self) -> tuple[tuple[float, float, float], tuple[float, float, float]]: """Resolve initial camera pose from config or USD camera path.""" - if self.cfg.camera_source == "usd_path": - pose = self._resolve_camera_pose_from_usd_path(self.cfg.camera_usd_path) + if self.cfg.cam_source == "prim_path": + pose = self._resolve_camera_pose_from_usd_path(self.cfg.cam_prim_path) if pose is not None: return pose + raise RuntimeError( + "[RerunVisualizer] cam_source='prim_path' requires a resolvable camera prim path, " + f"but no camera pose was found for '{self.cfg.cam_prim_path}'." + ) return self._resolve_cfg_camera_pose("RerunVisualizer") def _apply_camera_pose(self, pose: tuple[tuple[float, float, float], tuple[float, float, float]]) -> None: @@ -309,7 +312,7 @@ def _apply_camera_pose(self, pose: tuple[tuple[float, float, float], tuple[float def _update_camera_from_usd_path(self) -> None: """Refresh camera pose from configured USD camera path when it changes.""" - pose = self._resolve_camera_pose_from_usd_path(self.cfg.camera_usd_path) + pose = self._resolve_camera_pose_from_usd_path(self.cfg.cam_prim_path) if pose is None: return if self._last_camera_pose == pose: diff --git a/source/isaaclab_visualizers/isaaclab_visualizers/viser/viser_visualizer.py b/source/isaaclab_visualizers/isaaclab_visualizers/viser/viser_visualizer.py index d2cf60fd2c66..d6606403bba6 100644 --- a/source/isaaclab_visualizers/isaaclab_visualizers/viser/viser_visualizer.py +++ b/source/isaaclab_visualizers/isaaclab_visualizers/viser/viser_visualizer.py @@ -164,7 +164,7 @@ def initialize(self, scene_data_provider: BaseSceneDataProvider) -> None: rows=[ ("eye", self.cfg.eye), ("lookat", self.cfg.lookat), - ("camera_source", self.cfg.camera_source), + ("cam_source", self.cfg.cam_source), ("num_visualized_envs", num_visualized_envs), ("port", self.cfg.port), ("viewer_url", viewer_url), @@ -182,7 +182,7 @@ def step(self, dt: float) -> None: if not self._is_initialized or self._viewer is None or self._scene_data_provider is None: return - if self.cfg.camera_source == "usd_path": + if self.cfg.cam_source == "prim_path": self._update_camera_from_usd_path() self._apply_pending_camera_pose() @@ -260,8 +260,7 @@ def _create_viewer(self, record_to_viser: str | None, metadata: dict | None = No if self.cfg.open_browser: _open_viser_web_viewer(self.cfg.port) initial_pose = self._resolve_initial_camera_pose() - if initial_pose is not None: - self._set_viser_camera_view(initial_pose) + self._set_viser_camera_view(initial_pose) self._sim_time = 0.0 def _close_viewer(self, finalize_viser: bool = False) -> None: @@ -277,15 +276,15 @@ def _close_viewer(self, finalize_viser: bool = False) -> None: logger.warning("[ViserVisualizer] Recording file not found: %s", self._active_record_path) self._viewer = None - def _resolve_initial_camera_pose(self) -> tuple[tuple[float, float, float], tuple[float, float, float]] | None: + def _resolve_initial_camera_pose(self) -> tuple[tuple[float, float, float], tuple[float, float, float]]: """Resolve initial camera pose from config or USD camera path.""" - if self.cfg.camera_source == "usd_path": - pose = self._resolve_camera_pose_from_usd_path(self.cfg.camera_usd_path) + if self.cfg.cam_source == "prim_path": + pose = self._resolve_camera_pose_from_usd_path(self.cfg.cam_prim_path) if pose is not None: return pose - logger.warning( - "[ViserVisualizer] camera_usd_path '%s' not found; using configured camera.", - self.cfg.camera_usd_path, + raise RuntimeError( + "[ViserVisualizer] cam_source='prim_path' requires a resolvable camera prim path, " + f"but no camera pose was found for '{self.cfg.cam_prim_path}'." ) return self._resolve_cfg_camera_pose("ViserVisualizer") @@ -343,7 +342,7 @@ def _apply_pending_camera_pose(self) -> None: def _update_camera_from_usd_path(self) -> None: """Refresh camera pose from configured USD camera path when it changes.""" - pose = self._resolve_camera_pose_from_usd_path(self.cfg.camera_usd_path) + pose = self._resolve_camera_pose_from_usd_path(self.cfg.cam_prim_path) if pose is None: return if self._last_camera_pose == pose or self._pending_camera_pose == pose: From 34ef42dc5d01f82f52a75425163d426d35ff39e2 Mon Sep 17 00:00:00 2001 From: Matthew Trepte Date: Thu, 2 Apr 2026 22:38:58 +0000 Subject: [PATCH 10/11] init bug fix for stale renderer images after reset w/o kit viz --- source/isaaclab/isaaclab/envs/common.py | 2 +- .../isaaclab/isaaclab/envs/direct_marl_env.py | 9 ++------- .../isaaclab/isaaclab/envs/direct_rl_env.py | 9 ++------- .../isaaclab/envs/manager_based_env.py | 4 +--- .../isaaclab/envs/manager_based_rl_env.py | 5 +---- .../isaaclab/sim/simulation_context.py | 20 +++++++++++++++++++ .../renderers/isaac_rtx_renderer_utils.py | 17 ++++++++-------- 7 files changed, 36 insertions(+), 30 deletions(-) diff --git a/source/isaaclab/isaaclab/envs/common.py b/source/isaaclab/isaaclab/envs/common.py index 1af713a0eed0..f913005d1dbb 100644 --- a/source/isaaclab/isaaclab/envs/common.py +++ b/source/isaaclab/isaaclab/envs/common.py @@ -38,7 +38,7 @@ class ViewerCfg: """ origin_type: Literal["world", "env", "asset_root", "asset_body"] = "world" - """The frame in which the camera eye and lookat are defined in. Default is "world". + """The frame in which the camera position (eye) and target (lookat) are defined in. Default is "world". Available options are: diff --git a/source/isaaclab/isaaclab/envs/direct_marl_env.py b/source/isaaclab/isaaclab/envs/direct_marl_env.py index 31df5ee4155d..6c237d3bb974 100644 --- a/source/isaaclab/isaaclab/envs/direct_marl_env.py +++ b/source/isaaclab/isaaclab/envs/direct_marl_env.py @@ -152,9 +152,7 @@ def _init_sim(self, render_mode: str | None = None, **kwargs): # non-rendering modes. # Initialize when GUI is available OR when visualizers are active (headless rendering) # ViewerCfg camera updates are applied through renderer camera control. - has_visualizers = bool(self.sim.get_setting("/isaaclab/visualizer/types")) or bool( - self.sim.get_setting("/isaaclab/video/auto_start_kit") - ) + has_visualizers = self.sim.has_active_visualizers() if self.sim.has_gui or has_visualizers: self.viewport_camera_controller = ViewportCameraController(self, self.cfg.viewer) else: @@ -524,10 +522,7 @@ def render(self, recompute: bool = False) -> np.ndarray | None: return None elif self.render_mode == "rgb_array": # check that if any render could have happened - has_visualizers = bool(self.sim.get_setting("/isaaclab/visualizer/types")) or bool( - self.sim.get_setting("/isaaclab/video/auto_start_kit") - ) - if not (self.sim.has_gui or self.sim.has_offscreen_render or has_visualizers): + if not self.sim.can_render_rgb_array(): raise RuntimeError( f"Cannot render '{self.render_mode}' - no GUI and offscreen rendering not enabled." " If running headless, make sure --enable_cameras is set." diff --git a/source/isaaclab/isaaclab/envs/direct_rl_env.py b/source/isaaclab/isaaclab/envs/direct_rl_env.py index d2a220f1d0bd..f4ac159802bd 100644 --- a/source/isaaclab/isaaclab/envs/direct_rl_env.py +++ b/source/isaaclab/isaaclab/envs/direct_rl_env.py @@ -157,9 +157,7 @@ def _init_sim(self, render_mode: str | None = None, **kwargs): # non-rendering modes. # Initialize when GUI is available OR when visualizers are active (headless rendering) # ViewerCfg camera updates are applied through renderer camera control. - has_visualizers = bool(self.sim.get_setting("/isaaclab/visualizer/types")) or bool( - self.sim.get_setting("/isaaclab/video/auto_start_kit") - ) + has_visualizers = self.sim.has_active_visualizers() if self.sim.has_gui or has_visualizers: self.viewport_camera_controller = ViewportCameraController(self, self.cfg.viewer) else: @@ -492,10 +490,7 @@ def render(self, recompute: bool = False) -> np.ndarray | None: return None elif self.render_mode == "rgb_array": # check that if any render could have happened - has_visualizers = bool(self.sim.get_setting("/isaaclab/visualizer/types")) or bool( - self.sim.get_setting("/isaaclab/video/auto_start_kit") - ) - if not (self.sim.has_gui or self.sim.has_offscreen_render or has_visualizers): + if not self.sim.can_render_rgb_array(): raise RuntimeError( f"Cannot render '{self.render_mode}' - no GUI and offscreen rendering not enabled." " If running headless, make sure --enable_cameras is set." diff --git a/source/isaaclab/isaaclab/envs/manager_based_env.py b/source/isaaclab/isaaclab/envs/manager_based_env.py index 05b267df8a50..51fe7c329c8a 100644 --- a/source/isaaclab/isaaclab/envs/manager_based_env.py +++ b/source/isaaclab/isaaclab/envs/manager_based_env.py @@ -167,9 +167,7 @@ def _init_sim(self): # non-rendering modes. # Initialize when GUI is available OR when visualizers are active (headless rendering) # ViewerCfg camera updates are applied through renderer camera control. - has_visualizers = bool(self.sim.get_setting("/isaaclab/visualizer/types")) or bool( - self.sim.get_setting("/isaaclab/video/auto_start_kit") - ) + has_visualizers = self.sim.has_active_visualizers() if self.sim.has_gui or has_visualizers: self.viewport_camera_controller = ViewportCameraController(self, self.cfg.viewer) else: diff --git a/source/isaaclab/isaaclab/envs/manager_based_rl_env.py b/source/isaaclab/isaaclab/envs/manager_based_rl_env.py index 45c08746c762..37698d0d25eb 100644 --- a/source/isaaclab/isaaclab/envs/manager_based_rl_env.py +++ b/source/isaaclab/isaaclab/envs/manager_based_rl_env.py @@ -275,10 +275,7 @@ def render(self, recompute: bool = False) -> np.ndarray | None: elif self.render_mode == "rgb_array": # check that if any render could have happened # Check for GUI, offscreen rendering, or visualizers - has_visualizers = bool(self.sim.get_setting("/isaaclab/visualizer/types")) or bool( - self.sim.get_setting("/isaaclab/video/auto_start_kit") - ) - if not (self.sim.has_gui or self.sim.has_offscreen_render or has_visualizers): + if not self.sim.can_render_rgb_array(): raise RuntimeError( f"Cannot render '{self.render_mode}' - no GUI and offscreen rendering not enabled." " If running headless, make sure --enable_cameras is set." diff --git a/source/isaaclab/isaaclab/sim/simulation_context.py b/source/isaaclab/isaaclab/sim/simulation_context.py index 30cd1410e68a..13470e25cc2f 100644 --- a/source/isaaclab/isaaclab/sim/simulation_context.py +++ b/source/isaaclab/isaaclab/sim/simulation_context.py @@ -190,6 +190,10 @@ def __init__(self, cfg: SimulationCfg | None = None): # Monotonic physics-step counter used by camera sensors for self._physics_step_count: int = 0 + # Monotonic render-generation counter. This increments whenever render() + # is executed and lets downstream camera freshness logic distinguish + # render/reset transitions that occur without advancing physics steps. + self._render_generation: int = 0 type(self)._instance = self # Mark as valid singleton only after successful init @@ -339,6 +343,16 @@ def has_offscreen_render(self) -> bool: """Returns whether offscreen rendering is enabled (cached at init).""" return self._has_offscreen_render + def has_active_visualizers(self) -> bool: + """Return whether any visualizer path is active for rendering/camera control.""" + return bool(self.get_setting("/isaaclab/visualizer/types")) or bool( + self.get_setting("/isaaclab/video/auto_start_kit") + ) + + def can_render_rgb_array(self) -> bool: + """Return whether rgb-array rendering is currently available.""" + return self.has_gui or self.has_offscreen_render or self.has_active_visualizers() + @property def is_rendering(self) -> bool: """Returns whether rendering is active (GUI, RTX sensors, visualizers, or XR).""" @@ -354,6 +368,11 @@ def get_physics_dt(self) -> float: """Returns the physics time step.""" return self.physics_manager.get_physics_dt() + @property + def render_generation(self) -> int: + """Returns a monotonic counter for render() executions.""" + return self._render_generation + def _create_default_visualizer_configs(self, requested_visualizers: list[str]) -> list: """Create default visualizer configs for requested types. @@ -719,6 +738,7 @@ def render(self, mode: int | None = None) -> None: """ self.physics_manager.pre_render() self.update_visualizers(self.get_rendering_dt()) + self._render_generation += 1 # Call render callbacks if hasattr(self, "_render_callbacks"): diff --git a/source/isaaclab_physx/isaaclab_physx/renderers/isaac_rtx_renderer_utils.py b/source/isaaclab_physx/isaaclab_physx/renderers/isaac_rtx_renderer_utils.py index 8e5b9abc8549..8c848be42094 100644 --- a/source/isaaclab_physx/isaaclab_physx/renderers/isaac_rtx_renderer_utils.py +++ b/source/isaaclab_physx/isaaclab_physx/renderers/isaac_rtx_renderer_utils.py @@ -14,11 +14,11 @@ logger = logging.getLogger(__name__) -# Module-level dedup stamp: tracks the last (sim instance, physics step) at +# Module-level dedup stamp: tracks the last (sim instance, physics step, render generation) at # which Kit's ``app.update()`` was pumped. Keyed on ``id(sim)`` so that a # new ``SimulationContext`` (e.g. in a new test) automatically invalidates # any stale stamp from a previous instance. -_last_render_update_key: tuple[int, int] = (0, -1) +_last_render_update_key: tuple[int, int, int] = (0, -1, -1) # --------------------------------------------------------------------------- # RTX streaming status tracking @@ -91,7 +91,7 @@ def _wait_for_streaming_complete() -> None: def ensure_isaac_rtx_render_update() -> None: - """Ensure the Isaac RTX renderer has been pumped for the current physics step. + """Ensure the Isaac RTX renderer has been pumped for the current sim step. This keeps the Kit-specific ``app.update()`` logic inside the renderers package rather than in the backend-agnostic ``SimulationContext``. @@ -99,11 +99,11 @@ def ensure_isaac_rtx_render_update() -> None: Safe to call from multiple ``Camera`` / ``TiledCamera`` instances per step — only the first call triggers ``app.update()``. Subsequent calls are no-ops because the module-level ``_last_render_update_key`` already matches the - current ``(id(sim), step_count)`` pair. + current ``(id(sim), step_count, render_generation)`` tuple. - The key is a ``(sim_instance_id, step_count)`` tuple so that creating a new - ``SimulationContext`` (e.g. in a subsequent test) automatically invalidates - any stale stamp left over from a previous instance. + The key is a ``(sim_instance_id, step_count, render_generation)`` tuple so that: + - creating a new ``SimulationContext`` invalidates stale stamps, and + - render/reset transitions that do not advance physics step count still force a fresh update. If RTX texture/geometry streaming is in progress, additional ``app.update()`` calls are pumped until the streaming subsystem reports @@ -120,7 +120,8 @@ def ensure_isaac_rtx_render_update() -> None: if sim is None: return - key = (id(sim), sim._physics_step_count) + render_generation = getattr(sim, "render_generation", getattr(sim, "_render_generation", 0)) + key = (id(sim), sim._physics_step_count, render_generation) if _last_render_update_key == key: return # Already pumped this step (by another camera or a visualizer) From 3dd079a8ad69f9dad9db99ddda757cf7b0f95693 Mon Sep 17 00:00:00 2001 From: Matthew Trepte Date: Fri, 3 Apr 2026 00:16:36 +0000 Subject: [PATCH 11/11] clean --- .../isaaclab/visualizers/visualizer_cfg.py | 2 +- .../isaaclab_mimic/datagen/generation.py | 83 +++++++++++++++++++ .../kit/kit_visualizer_cfg.py | 4 +- 3 files changed, 86 insertions(+), 3 deletions(-) diff --git a/source/isaaclab/isaaclab/visualizers/visualizer_cfg.py b/source/isaaclab/isaaclab/visualizers/visualizer_cfg.py index 0bd362e4ccd9..3f62c3e5232e 100644 --- a/source/isaaclab/isaaclab/visualizers/visualizer_cfg.py +++ b/source/isaaclab/isaaclab/visualizers/visualizer_cfg.py @@ -34,7 +34,7 @@ class VisualizerCfg: enable_live_plots: bool = True """Enable live plotting of data.""" - eye: tuple[float, float, float] = (8.0, 8.0, 3.0) + eye: tuple[float, float, float] = (7.5, 7.5, 7.5) """Initial camera eye position (x, y, z) in world coordinates.""" lookat: tuple[float, float, float] = (0.0, 0.0, 0.0) diff --git a/source/isaaclab_mimic/isaaclab_mimic/datagen/generation.py b/source/isaaclab_mimic/isaaclab_mimic/datagen/generation.py index 71bb5e9925cd..bc923c4b9a21 100644 --- a/source/isaaclab_mimic/isaaclab_mimic/datagen/generation.py +++ b/source/isaaclab_mimic/isaaclab_mimic/datagen/generation.py @@ -5,16 +5,19 @@ import asyncio import contextlib +import os import sys import traceback from typing import Any import torch +import warp as wp from isaaclab.envs import ManagerBasedRLMimicEnv from isaaclab.envs.mdp.recorders.recorders_cfg import ActionStateRecorderManagerCfg from isaaclab.managers import DatasetExportMode, TerminationTermCfg from isaaclab.managers.recorder_manager import RecorderManagerBaseCfg +from isaaclab.utils.math import subtract_frame_transforms from isaaclab_mimic.datagen.data_generator import DataGenerator from isaaclab_mimic.datagen.datagen_info_pool import DataGenInfoPool @@ -27,6 +30,59 @@ num_attempts = 0 +def _debug_wrist_cam_pose(env: ManagerBasedRLMimicEnv, env_id: int, tag: str, hand_body_idx: int | None): + """Print wrist camera and hand-link transforms for debugging camera alignment.""" + try: + if "wrist_cam" not in env.scene.keys() or "robot" not in env.scene.keys(): + print(f"[WRIST_CAM_DEBUG] {tag} env={env_id} missing wrist_cam or robot in scene") + return + + wrist_cam = env.scene["wrist_cam"] + robot = env.scene["robot"] + cam_pos = wrist_cam.data.pos_w[env_id].detach().cpu() + cam_quat = wrist_cam.data.quat_w_world[env_id].detach().cpu() + cam_frame = int(wrist_cam.frame[env_id].item()) if wrist_cam.frame.numel() > env_id else -1 + live_pos_all, live_quat_all = wrist_cam._view.get_world_poses([env_id]) + live_cam_pos = live_pos_all[0].detach().cpu() + live_cam_quat = live_quat_all[0].detach().cpu() + + if hand_body_idx is None: + print( + f"[WRIST_CAM_DEBUG] {tag} env={env_id} cam_frame={cam_frame} " + f"cam_pos={cam_pos.tolist()} cam_quat_xyzw={cam_quat.tolist()} " + f"live_cam_pos={live_cam_pos.tolist()} live_cam_quat_xyzw={live_cam_quat.tolist()} " + f"hand_body_idx=None" + ) + return + + hand_pos = wp.to_torch(robot.data.body_pos_w)[env_id, hand_body_idx].detach().cpu() + hand_quat = wp.to_torch(robot.data.body_quat_w)[env_id, hand_body_idx].detach().cpu() + rel_pos, rel_quat = subtract_frame_transforms( + hand_pos.unsqueeze(0), + hand_quat.unsqueeze(0), + cam_pos.unsqueeze(0), + cam_quat.unsqueeze(0), + ) + live_rel_pos, live_rel_quat = subtract_frame_transforms( + hand_pos.unsqueeze(0), + hand_quat.unsqueeze(0), + live_cam_pos.unsqueeze(0), + live_cam_quat.unsqueeze(0), + ) + print( + f"[WRIST_CAM_DEBUG] {tag} env={env_id} cam_frame={cam_frame} " + f"cam_pos={cam_pos.tolist()} cam_quat_xyzw={cam_quat.tolist()} " + f"live_cam_pos={live_cam_pos.tolist()} live_cam_quat_xyzw={live_cam_quat.tolist()} " + f"hand_pos={hand_pos.tolist()} hand_quat_xyzw={hand_quat.tolist()} " + f"cam_rel_hand_pos={rel_pos[0].detach().cpu().tolist()} " + f"cam_rel_hand_quat_xyzw={rel_quat[0].detach().cpu().tolist()} " + f"live_cam_rel_hand_pos={live_rel_pos[0].detach().cpu().tolist()} " + f"live_cam_rel_hand_quat_xyzw={live_rel_quat[0].detach().cpu().tolist()}" + ) + except Exception as exc: + print(f"[WRIST_CAM_DEBUG] {tag} env={env_id} logging_failed={exc}") + + async def run_data_generator( env: ManagerBasedRLMimicEnv, env_id: int, @@ -91,6 +147,18 @@ def env_loop( global num_success, num_failures, num_attempts env_id_tensor = torch.tensor([0], dtype=torch.int64, device=env.device) prev_num_attempts = 0 + debug_wrist_cam = os.environ.get("ISAACLAB_DEBUG_WRIST_CAM", "0") == "1" + post_reset_step_counters = [0 for _ in range(env.num_envs)] + hand_body_idx = None + if debug_wrist_cam: + try: + if "robot" in env.scene.keys(): + body_ids, _ = env.scene["robot"].find_bodies("panda_hand") + hand_body_idx = int(body_ids[0]) if len(body_ids) > 0 else None + print(f"[WRIST_CAM_DEBUG] enabled=1 hand_body_idx={hand_body_idx}") + except Exception as exc: + print(f"[WRIST_CAM_DEBUG] enabled=1 hand_body_idx_lookup_failed={exc}") + # simulate environment -- run everything in inference mode with contextlib.suppress(KeyboardInterrupt) and torch.inference_mode(): while True: @@ -100,6 +168,11 @@ def env_loop( while not env_reset_queue.empty(): env_id_tensor[0] = env_reset_queue.get_nowait() env.reset(env_ids=env_id_tensor) + reset_env_id = int(env_id_tensor[0].item()) + if 0 <= reset_env_id < env.num_envs: + post_reset_step_counters[reset_env_id] = 0 + if debug_wrist_cam: + _debug_wrist_cam_pose(env, reset_env_id, tag="after_reset", hand_body_idx=hand_body_idx) env_reset_queue.task_done() actions = torch.zeros(env.action_space.shape) @@ -112,6 +185,16 @@ def env_loop( # perform action on environment env.step(actions) + if debug_wrist_cam: + for env_id in range(env.num_envs): + if post_reset_step_counters[env_id] <= 1: + _debug_wrist_cam_pose( + env, + env_id, + tag=f"after_step_{post_reset_step_counters[env_id]}", + hand_body_idx=hand_body_idx, + ) + post_reset_step_counters[env_id] += 1 # mark done so the data generators can continue with the step results for i in range(env.num_envs): diff --git a/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualizer_cfg.py b/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualizer_cfg.py index 921dc42fc11c..d3fea2e0da6b 100644 --- a/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualizer_cfg.py +++ b/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualizer_cfg.py @@ -19,13 +19,13 @@ class KitVisualizerCfg(VisualizerCfg): viewport_name: str = "Visualizer Viewport" """Viewport name to use when :attr:`create_viewport` is True.""" - create_viewport: bool = False + create_viewport: bool = True """Create new viewport with specified name and camera pose.""" visualizer_camera_prim_path: str = "/World/Cameras/KitVisualizerCamera" """Dedicated camera prim path controlled by the Kit visualizer.""" - enable_visualizer_cam: bool = False + enable_visualizer_cam: bool = True """Whether the Kit visualizer should control/bind a dedicated viewport camera. If False, Kit does not create/switch camera prims and ignores visualizer camera control