diff --git a/docs/source/features/visualization.rst b/docs/source/features/visualization.rst index 13d573308ef..1af532c9df5 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 @@ -217,7 +217,7 @@ Newton Visualizer - Lightweight OpenGL rendering with low overhead - Visualization markers (joints, contacts, springs, COM) -- Training and rendering pause controls +- Simulation and rendering pause controls - Adjustable update frequency for performance tuning - Some customizable rendering options (shadows, sky, wireframe) @@ -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 @@ -393,12 +393,6 @@ the num of environments can be overwritten and decreased using ``--num_envs``: python scripts/reinforcement_learning/rsl_rl/train.py --task Isaac-Cartpole-v0 --viz rerun --num_envs 512 -.. note:: - - A future feature will support visualizing only a subset of environments, which will improve visualization performance - and reduce resource usage while maintaining full-scale training in the background. - - **Rerun Visualizer FPS Control** The FPS control in the Rerun visualizer UI may not affect the visualization frame rate in all configurations. diff --git a/source/isaaclab/isaaclab/app/app_launcher.py b/source/isaaclab/isaaclab/app/app_launcher.py index df6f7cb79e1..dcc8d1ca53e 100644 --- a/source/isaaclab/isaaclab/app/app_launcher.py +++ b/source/isaaclab/isaaclab/app/app_launcher.py @@ -189,6 +189,7 @@ 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 # Exposed to train scripts self.device_id: int # device ID for GPU simulation (defaults to 0) @@ -858,12 +859,13 @@ 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 # hide_ui flag @@ -1085,6 +1087,8 @@ 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 + settings.set_bool("/isaaclab/video/enabled", self._video_enabled) # 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/cli/commands/install.py b/source/isaaclab/isaaclab/cli/commands/install.py index c442cfd89fe..1ee0c8cd017 100644 --- a/source/isaaclab/isaaclab/cli/commands/install.py +++ b/source/isaaclab/isaaclab/cli/commands/install.py @@ -305,6 +305,9 @@ def _install_extra_frameworks(framework_name: str = "all") -> None: "newton_actuators", "warp", "mujoco_warp", + "websockets", + "viser", + "imgui_bundle", ] """Package directory names in Isaac Sim prebundle directories to repoint. @@ -352,7 +355,25 @@ def _repoint_prebundle_packages() -> None: print_warning(f"site-packages directory not found: {site_packages} — skipping prebundle repoint.") return - prebundle_dirs = list(isaacsim_path.rglob("pip_prebundle")) + # Discover pip_prebundle directories from both the Isaac Sim tree and + # Omniverse cache roots. Some Isaac Sim directories are symlinked into + # ~/.local/share/ov and may be missed by a plain rglob() on _isaac_sim. + candidate_roots: set[Path] = set() + for root in ( + isaacsim_path, + isaacsim_path.resolve(), + isaacsim_path / "extscache", + Path.home() / ".local" / "share" / "ov" / "data" / "exts", + Path.home() / ".local" / "share" / "ov" / "data" / "exts" / "v2", + ): + if root.exists(): + candidate_roots.add(root) + candidate_roots.add(root.resolve()) + + prebundle_dirs: set[Path] = set() + for root in candidate_roots: + prebundle_dirs.update(root.rglob("pip_prebundle")) + if not prebundle_dirs: print_debug("No pip_prebundle directories found under Isaac Sim.") return diff --git a/source/isaaclab/isaaclab/envs/common.py b/source/isaaclab/isaaclab/envs/common.py index f913005d1db..033b9c38610 100644 --- a/source/isaaclab/isaaclab/envs/common.py +++ b/source/isaaclab/isaaclab/envs/common.py @@ -5,6 +5,8 @@ from __future__ import annotations +import warnings +from dataclasses import MISSING, fields from typing import Dict, Literal, TypeVar # noqa: UP035 import gymnasium as gym @@ -17,9 +19,28 @@ ## +def _viewer_cfg_value_matches_default(current: object, default: object) -> bool: + """Return True if ``current`` matches the dataclass field default (including list/tuple equivalence).""" + if current == default: + return True + if isinstance(current, (list, tuple)) and isinstance(default, (list, tuple)): + if len(current) != len(default): + return False + return all(a == b for a, b in zip(current, default, strict=True)) + return False + + @configclass class ViewerCfg: - """Configuration of the scene viewport camera.""" + """Configuration of the scene viewport camera. + + Note: + Overriding non-default fields is deprecated. In a future release, Isaac Sim viewport camera + configuration will be expressed only through ``KitVisualizerCfg`` under + ``SimulationCfg.visualizer_cfgs``; use ``NewtonVisualizerCfg`` for the Newton viewer. + Those visualizer configs replace the viewport camera pose, resolution, prim path, and + frame-origin behavior that this class used to configure. + """ eye: tuple[float, float, float] = (7.5, 7.5, 7.5) """Initial camera position (in m). Default is (7.5, 7.5, 7.5).""" @@ -67,6 +88,35 @@ class ViewerCfg: This quantity is only effective if :attr:`origin` is set to "asset_body". """ + def __post_init__(self) -> None: + # Dataclasses do not record which arguments were passed explicitly vs defaulted, and + # warning only on ``**kwargs`` would miss positional arguments. Comparing each field to + # its declared default catches any non-default effective configuration (including + # ``replace()`` and ``from_dict``), while keeping ``ViewerCfg()`` silent. + differing: list[str] = [] + for f in fields(self): + if not f.init: + continue + if f.default is not MISSING: + default_val = f.default + elif f.default_factory is not MISSING: + default_val = f.default_factory() + else: + continue + if not _viewer_cfg_value_matches_default(getattr(self, f.name), default_val): + differing.append(f.name) + if differing: + warnings.warn( + "ViewerCfg is deprecated when overriding default viewport camera fields " + f"({', '.join(sorted(differing))}). In a future release, Isaac Sim viewport camera " + "settings will be configured only through ``SimulationCfg.visualizer_cfgs`` using " + "``KitVisualizerCfg`` (viewport camera pose, resolution, prim path, and " + "frame-origin options). For the Newton viewer, use ``NewtonVisualizerCfg``. " + "Migrate overrides out of ``ViewerCfg`` accordingly.", + DeprecationWarning, + stacklevel=2, + ) + ## # Types. diff --git a/source/isaaclab/isaaclab/envs/direct_marl_env.py b/source/isaaclab/isaaclab/envs/direct_marl_env.py index c6009117f1b..b325164ebe0 100644 --- a/source/isaaclab/isaaclab/envs/direct_marl_env.py +++ b/source/isaaclab/isaaclab/envs/direct_marl_env.py @@ -151,10 +151,10 @@ def _init_sim(self, render_mode: str | None = None, **kwargs): # viewport is not available in other rendering modes so the function will throw a warning # FIXME: This needs to be fixed in the future when we unify the UI functionalities even for # non-rendering modes. - # 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")) - if self.sim.has_gui or has_visualizers: + # Initialize when a Kit viewport exists. ViewportCameraController uses omni.kit (renderer camera); + # skip in kitless Newton-only runs (e.g. --viz rerun) where no Kit app is running. + has_visualizers = self.sim.has_active_visualizers() + if (self.sim.has_gui or has_visualizers) and has_kit(): self.viewport_camera_controller = ViewportCameraController(self, self.cfg.viewer) else: self.viewport_camera_controller = None diff --git a/source/isaaclab/isaaclab/envs/direct_rl_env.py b/source/isaaclab/isaaclab/envs/direct_rl_env.py index 05dc8495dbc..c67803ff8cf 100644 --- a/source/isaaclab/isaaclab/envs/direct_rl_env.py +++ b/source/isaaclab/isaaclab/envs/direct_rl_env.py @@ -156,10 +156,10 @@ def _init_sim(self, render_mode: str | None = None, **kwargs): # viewport is not available in other rendering modes so the function will throw a warning # FIXME: This needs to be fixed in the future when we unify the UI functionalities even for # non-rendering modes. - # 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")) - if self.sim.has_gui or has_visualizers: + # Initialize when a Kit viewport exists. ViewportCameraController uses omni.kit (renderer camera); + # skip in kitless Newton-only runs (e.g. --viz rerun) where no Kit app is running. + has_visualizers = self.sim.has_active_visualizers() + if (self.sim.has_gui or has_visualizers) and has_kit(): self.viewport_camera_controller = ViewportCameraController(self, self.cfg.viewer) else: self.viewport_camera_controller = None diff --git a/source/isaaclab/isaaclab/envs/manager_based_env.py b/source/isaaclab/isaaclab/envs/manager_based_env.py index 1e8ca057610..c63db4922c9 100644 --- a/source/isaaclab/isaaclab/envs/manager_based_env.py +++ b/source/isaaclab/isaaclab/envs/manager_based_env.py @@ -21,6 +21,7 @@ from isaaclab.utils.configclass import resolve_cfg_presets from isaaclab.utils.seed import configure_seed from isaaclab.utils.timer import Timer +from isaaclab.utils.version import has_kit from .common import VecEnvObs from .manager_based_env_cfg import ManagerBasedEnvCfg @@ -166,10 +167,10 @@ def _init_sim(self): # viewport is not available in other rendering modes so the function will throw a warning # FIXME: This needs to be fixed in the future when we unify the UI functionalities even for # non-rendering modes. - # 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")) - if self.sim.has_gui or has_visualizers: + # Initialize when a Kit viewport exists. ViewportCameraController uses omni.kit (renderer camera); + # skip in kitless Newton-only runs (e.g. --viz rerun) where no Kit app is running. + has_visualizers = self.sim.has_active_visualizers() + if (self.sim.has_gui or has_visualizers) and has_kit(): self.viewport_camera_controller = ViewportCameraController(self, self.cfg.viewer) else: self.viewport_camera_controller = None diff --git a/source/isaaclab/isaaclab/envs/ui/viewport_camera_controller.py b/source/isaaclab/isaaclab/envs/ui/viewport_camera_controller.py index 4126d7b7473..48f4c3f159a 100644 --- a/source/isaaclab/isaaclab/envs/ui/viewport_camera_controller.py +++ b/source/isaaclab/isaaclab/envs/ui/viewport_camera_controller.py @@ -218,8 +218,11 @@ 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) + # Kit-specific helper lives in isaaclab_physx + from isaaclab_physx.renderers.kit_viewport_utils import set_kit_renderer_camera_view + + set_kit_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/envs/utils/recording_hooks.py b/source/isaaclab/isaaclab/envs/utils/recording_hooks.py new file mode 100644 index 00000000000..584b6d73adf --- /dev/null +++ b/source/isaaclab/isaaclab/envs/utils/recording_hooks.py @@ -0,0 +1,50 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Hooks that run after visualizers during :meth:`~isaaclab.sim.SimulationContext.render`. + +Lives alongside :mod:`video_recorder` / :mod:`video_recorder_cfg` because both tie into +``--video`` / ``rgb_array`` recording. Keeps :class:`~isaaclab.sim.SimulationContext` free +of imports from ``isaaclab_physx``, ``isaaclab_newton``, and other recording backends. +Each integration is loaded lazily so optional extensions are not required at import time. +""" + +from __future__ import annotations + +from typing import Any + + +def run_recording_hooks_after_visualizers(sim: Any) -> None: + """Run recording-related work after :meth:`~isaaclab.sim.SimulationContext.render` steps visualizers. + + Isaac Sim / RTX follow-up is loaded lazily so minimal installs still work. + Newton GL video is handled by :class:`~isaaclab.envs.utils.video_recorder.VideoRecorder` + (e.g. :class:`~isaaclab_newton.video_recording.newton_gl_perspective_video.NewtonGlPerspectiveVideo`), + not here. + + Args: + sim: Active :class:`~isaaclab.sim.SimulationContext` instance. + """ + _recording_followup_isaac_sim(sim) + + +def _recording_followup_isaac_sim(sim: Any) -> None: + """Isaac Sim: keep RTX / Replicator outputs fresh when recording video without a Kit visualizer. + + When ``--video`` uses ``rgb_array`` / :class:`~gymnasium.wrappers.RecordVideo`, Replicator + render products must see Kit's event loop pumped. :class:`~isaaclab_visualizers.kit.KitVisualizer` + already calls ``omni.kit.app.get_app().update()`` in its ``step()``; if no such visualizer + is active, we pump here (guarded by ``/isaaclab/video/enabled`` and ``is_rendering``). + + Implemented by ``pump_kit_app_for_headless_video_render_if_needed`` in + :mod:`isaaclab_physx.renderers.isaac_rtx_renderer_utils`. + """ + try: + from isaaclab_physx.renderers.isaac_rtx_renderer_utils import ( + pump_kit_app_for_headless_video_render_if_needed, + ) + except ImportError: + return + pump_kit_app_for_headless_video_render_if_needed(sim) diff --git a/source/isaaclab/isaaclab/physics/physics_manager.py b/source/isaaclab/isaaclab/physics/physics_manager.py index cc18582bc80..7a4cdfe8440 100644 --- a/source/isaaclab/isaaclab/physics/physics_manager.py +++ b/source/isaaclab/isaaclab/physics/physics_manager.py @@ -276,6 +276,16 @@ def pre_render(cls) -> None: """ pass + @classmethod + def after_visualizers_render(cls) -> None: + """Hook after visualizers have stepped during :meth:`~isaaclab.sim.SimulationContext.render`. + + Use for physics-backend sync (e.g. fabric) if needed. Recording pipelines (Kit/RTX, + Newton GL video, etc.) run from :mod:`isaaclab.envs.utils.recording_hooks` so they are not + tied to a specific physics manager. Default is a no-op. + """ + pass + @classmethod def close(cls) -> None: """Clean up physics resources. diff --git a/source/isaaclab/isaaclab/sim/simulation_context.py b/source/isaaclab/isaaclab/sim/simulation_context.py index a7fd7d632d3..d5c3ea84fc1 100644 --- a/source/isaaclab/isaaclab/sim/simulation_context.py +++ b/source/isaaclab/isaaclab/sim/simulation_context.py @@ -21,6 +21,7 @@ import isaaclab.sim as sim_utils import isaaclab.sim.utils.stage as stage_utils from isaaclab.app.settings_manager import SettingsManager +from isaaclab.envs.utils.recording_hooks import run_recording_hooks_after_visualizers from isaaclab.physics import BaseSceneDataProvider, PhysicsManager, SceneDataProvider from isaaclab.physics.scene_data_requirements import ( SceneDataRequirement, @@ -181,6 +182,7 @@ def __init__(self, cfg: SimulationCfg | None = None): self._has_offscreen_render = bool(self.get_setting("/isaaclab/render/offscreen")) self._xr_enabled = bool(self.get_setting("/isaaclab/xr/enabled")) # 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 @@ -188,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 @@ -289,10 +295,14 @@ def _init_usd_physics_scene(self) -> None: UsdGeom.SetStageMetersPerUnit(self.stage, 1.0) UsdPhysics.SetStageKilogramsPerUnit(self.stage, 1.0) - # Find and delete any existing physics scene - for prim in self.stage.Traverse(): - if prim.GetTypeName() == "PhysicsScene": - sim_utils.delete_prim(prim.GetPath().pathString, stage=self.stage) + # Find and delete any existing physics scene. + # Collect paths first to avoid mutating the stage while traversing, + # which can invalidate the USD iterator. + physics_scene_paths = [ + prim.GetPath().pathString for prim in self.stage.Traverse() if prim.GetTypeName() == "PhysicsScene" + ] + for physics_scene_path in physics_scene_paths: + sim_utils.delete_prim(physics_scene_path, stage=self.stage) # Create a new physics scene if self.stage.GetPrimAtPath(cfg.physics_prim_path).IsValid(): @@ -337,6 +347,10 @@ 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")) + @property def is_rendering(self) -> bool: """Returns whether rendering is active (GUI, RTX sensors, visualizers, or XR).""" @@ -352,6 +366,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. @@ -577,6 +596,14 @@ def initialize_visualizers(self) -> None: exc, ) + # Replay any camera pose requested before visualizers were initialized. + pending = getattr(self, "_pending_camera_view", None) + if pending is not None: + eye, target = pending + for viz in self._visualizers: + viz.set_camera_view(eye, target) + self._pending_camera_view = None + 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): @@ -627,6 +654,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) @@ -673,10 +701,15 @@ def render(self, mode: int | None = None) -> None: Calls update_visualizers() so visualizers run at the render cadence (not at every physics step). Camera sensors drive their configured renderer when - fetching data, so this method remains backend-agnostic. + fetching data. Recording-related follow-up (Kit/RTX headless video, Newton GL + video, etc.) runs in :mod:`isaaclab.envs.utils.recording_hooks` so it is not tied to a + specific :class:`~isaaclab.physics.PhysicsManager` subclass. """ self.physics_manager.pre_render() self.update_visualizers(self.get_rendering_dt()) + self.physics_manager.after_visualizers_render() + run_recording_hooks_after_visualizers(self) + self._render_generation += 1 # Call render callbacks if hasattr(self, "_render_callbacks"): @@ -701,6 +734,9 @@ def update_visualizers(self, dt: float) -> None: visualizers_to_remove.append(viz) continue if viz.is_rendering_paused(): + # Keep non-Kit visualizer event loops responsive while rendering is paused. + if not viz.pumps_app_update(): + viz.step(0.0) continue while viz.is_training_paused() and viz.is_running(): viz.step(0.0) diff --git a/source/isaaclab/isaaclab/visualizers/base_visualizer.py b/source/isaaclab/isaaclab/visualizers/base_visualizer.py index 2480bc89bba..e8a896ad562 100644 --- a/source/isaaclab/isaaclab/visualizers/base_visualizer.py +++ b/source/isaaclab/isaaclab/visualizers/base_visualizer.py @@ -187,6 +187,14 @@ 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]]: + """Resolve camera pose from cfg eye/lookat fields.""" + eye = tuple(float(v) for v in self.cfg.eye) + lookat = tuple(float(v) for v in self.cfg.lookat) + 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 a96e3c04d2b..3f62c3e5232 100644 --- a/source/isaaclab/isaaclab/visualizers/visualizer_cfg.py +++ b/source/isaaclab/isaaclab/visualizers/visualizer_cfg.py @@ -34,17 +34,17 @@ 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] = (7.5, 7.5, 7.5) + """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.""" + 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 camera_position/target, '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/test/sim/test_simulation_context.py b/source/isaaclab/test/sim/test_simulation_context.py index c03413838e3..6ea578a85e3 100644 --- a/source/isaaclab/test/sim/test_simulation_context.py +++ b/source/isaaclab/test/sim/test_simulation_context.py @@ -290,6 +290,86 @@ def test_render(): assert sim.is_playing() +@pytest.mark.isaacsim_ci +def test_render_pumps_app_update_without_visualizer(): + """Regression test for issue #5052: headless video must pump Kit when no visualizer does. + + Originally ``SimulationContext.render()`` called ``omni.kit.app.get_app().update()`` when + no visualizer had ``pumps_app_update()`` (see PR #5056). The same contract is now implemented + from :func:`~isaaclab.envs.utils.recording_hooks.run_recording_hooks_after_visualizers`, which calls + :func:`~isaaclab_physx.renderers.isaac_rtx_renderer_utils.pump_kit_app_for_headless_video_render_if_needed` + when ``/isaaclab/video/enabled`` is set (as with ``--video``), which in turn calls + ``ensure_isaac_rtx_render_update()`` (guarded by ``is_rendering`` and the no-pumping-visualizer check). + + Without this path, replicator render products used for ``rgb_array`` / RecordVideo stay stale (black frames). + """ + from unittest.mock import MagicMock, patch + + cfg = SimulationCfg(dt=0.01) + sim = SimulationContext(cfg) + sim.reset() + + sim.set_setting("/isaaclab/video/enabled", True) + sim.set_setting("/isaaclab/render/rtx_sensors", True) + + mock_app = MagicMock() + mock_app.is_running.return_value = True + + with ( + patch("isaaclab.utils.version.has_kit", return_value=True), + patch( + "isaaclab_physx.renderers.isaac_rtx_renderer_utils._get_stage_streaming_busy", + return_value=False, + ), + patch("omni.kit.app.get_app", return_value=mock_app), + ): + sim.render() + + mock_app.update.assert_called_once() + + +@pytest.mark.isaacsim_ci +def test_render_skips_app_update_when_visualizer_pumps_it(): + """Regression test: do not pump Kit in the headless-video path when a visualizer already does. + + A visualizer with ``pumps_app_update() == True`` (e.g. KitVisualizer) calls ``app.update()`` in + its own ``step()``. The recording-hook pump must then skip + ``ensure_isaac_rtx_render_update`` so we do not double-pump the Kit loop. + """ + from unittest.mock import MagicMock, patch + + from isaaclab.visualizers.base_visualizer import BaseVisualizer + + cfg = SimulationCfg(dt=0.01) + sim = SimulationContext(cfg) + sim.reset() + + sim.set_setting("/isaaclab/video/enabled", True) + sim.set_setting("/isaaclab/render/rtx_sensors", True) + + mock_viz = MagicMock(spec=BaseVisualizer) + mock_viz.pumps_app_update.return_value = True + mock_viz.is_closed = False + mock_viz.is_running.return_value = True + mock_viz.is_rendering_paused.return_value = False + mock_viz.is_training_paused.return_value = False + mock_viz.get_rendering_dt.return_value = None + sim._visualizers = [mock_viz] + + mock_app = MagicMock() + mock_app.is_running.return_value = True + + with ( + patch("isaaclab.utils.version.has_kit", return_value=True), + patch("omni.kit.app.get_app", return_value=mock_app), + ): + sim.render() + + mock_app.update.assert_not_called() + + sim._visualizers = [] + + """ Stage Operations Tests """ diff --git a/source/isaaclab/test/sim/test_simulation_context_visualizers.py b/source/isaaclab/test/sim/test_simulation_context_visualizers.py index f0a1294d2b4..07d9ab0cb4c 100644 --- a/source/isaaclab/test/sim/test_simulation_context_visualizers.py +++ b/source/isaaclab/test/sim/test_simulation_context_visualizers.py @@ -45,6 +45,7 @@ def __init__( training_paused_steps=0, raises_on_step=False, requires_forward=False, + pumps_app_update=False, ): self._env_ids = env_ids self._running = running @@ -53,6 +54,7 @@ def __init__( self._training_paused_steps = training_paused_steps self._raises_on_step = raises_on_step self._requires_forward = requires_forward + self._pumps_app_update = pumps_app_update self.step_calls = [] self.close_calls = 0 @@ -87,6 +89,9 @@ def get_visualized_env_ids(self): def requires_forward_before_step(self): return self._requires_forward + def pumps_app_update(self): + return self._pumps_app_update + def _make_context(visualizers, provider=None): ctx = object.__new__(SimulationContext) @@ -136,10 +141,21 @@ 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_skips_zero_dt_for_paused_app_pumping_visualizer(): + provider = _FakeProvider() + paused_app_pumping_viz = _FakeVisualizer(rendering_paused=True, pumps_app_update=True) + ctx = _make_context([paused_app_pumping_viz], provider=provider) + + ctx.update_visualizers(0.3) + + assert paused_app_pumping_viz.step_calls == [] + + def test_update_visualizers_handles_training_pause_loop(): provider = _FakeProvider() viz = _FakeVisualizer(training_paused_steps=1) @@ -398,6 +414,8 @@ def _make_context_with_settings( ctx._has_gui = has_gui ctx._has_offscreen_render = has_offscreen_render ctx._xr_enabled = False + ctx._pending_camera_view = None + ctx._render_generation = 0 ctx._visualizers = [] ctx._scene_data_provider = _FakeProvider() ctx._scene_data_requirements = None diff --git a/source/isaaclab/test/utils/test_configclass.py b/source/isaaclab/test/utils/test_configclass.py index 716c834cc3e..10380314892 100644 --- a/source/isaaclab/test/utils/test_configclass.py +++ b/source/isaaclab/test/utils/test_configclass.py @@ -584,7 +584,8 @@ def test_dict_conversion_order(): def test_config_update_via_constructor(): """Test updating configclass through initialization.""" - cfg = BasicDemoCfg(env=EnvCfg(num_envs=22, viewer=ViewerCfg(eye=(2.0, 2.0, 2.0)))) + with pytest.warns(DeprecationWarning, match="ViewerCfg is deprecated"): + cfg = BasicDemoCfg(env=EnvCfg(num_envs=22, viewer=ViewerCfg(eye=(2.0, 2.0, 2.0)))) assert asdict(cfg) == basic_demo_cfg_change_correct diff --git a/source/isaaclab_newton/isaaclab_newton/video_recording/__init__.py b/source/isaaclab_newton/isaaclab_newton/video_recording/__init__.py index 3248ca5f13b..1d5cb96e0ef 100644 --- a/source/isaaclab_newton/isaaclab_newton/video_recording/__init__.py +++ b/source/isaaclab_newton/isaaclab_newton/video_recording/__init__.py @@ -4,3 +4,8 @@ # SPDX-License-Identifier: BSD-3-Clause """Newton GL perspective video recording.""" + +from .newton_gl_perspective_video import NewtonGlPerspectiveVideo +from .newton_gl_perspective_video_cfg import NewtonGlPerspectiveVideoCfg + +__all__ = ["NewtonGlPerspectiveVideo", "NewtonGlPerspectiveVideoCfg"] diff --git a/source/isaaclab_newton/isaaclab_newton/video_recording/recording_hooks.py b/source/isaaclab_newton/isaaclab_newton/video_recording/recording_hooks.py new file mode 100644 index 00000000000..7efcae7b550 --- /dev/null +++ b/source/isaaclab_newton/isaaclab_newton/video_recording/recording_hooks.py @@ -0,0 +1,30 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Hooks for Newton-based video recording after visualizers have stepped.""" + +from __future__ import annotations + +from typing import TYPE_CHECKING + +if TYPE_CHECKING: + from isaaclab.sim import SimulationContext + + +def recording_followup_after_visualizers(sim: SimulationContext) -> None: + """Newton extension hook: recording pipeline after visualizers have stepped. + + Called from :func:`isaaclab.envs.utils.recording_hooks.run_recording_hooks_after_visualizers`. + Wire **Newton GL** / Newton-specific video capture here (e.g. perspective video, + frame sync with ``NewtonVisualizer``). Stay lightweight and no-op when Newton + recording is inactive. + + The Isaac Sim / RTX path (``omni.kit.app`` pump for Replicator ``rgb_array``) lives in + :mod:`isaaclab_physx.renderers.isaac_rtx_renderer_utils` — not here. + + Args: + sim: Active simulation context. + """ + _ = sim # Reserved until Newton GL video paths are hooked up. 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 032bf001c79..1a2379a39d5 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 @@ -9,16 +9,17 @@ import logging import time +from typing import Any import isaaclab.sim as sim_utils 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) _STREAMING_WAIT_TIMEOUT_S: float = 30.0 @@ -58,7 +59,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``. @@ -66,11 +67,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. After the initial ``app.update()`` the streaming subsystem is queried synchronously via ``UsdContext.get_stage_streaming_status()``. If textures @@ -88,7 +89,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) @@ -116,3 +118,25 @@ def ensure_isaac_rtx_render_update() -> None: sim.set_setting("/app/player/playSimulations", True) _last_render_update_key = key + + +def pump_kit_app_for_headless_video_render_if_needed(sim: Any) -> None: + """Pump Kit app-loop for headless rgb-array rendering when needed. + + Isaac Sim / RTX specific; kept out of backend-agnostic :class:`~isaaclab.sim.SimulationContext`. + """ + if not bool(sim.get_setting("/isaaclab/video/enabled")): + return + + from isaaclab.utils.version import has_kit + + if not has_kit(): + return + if any(viz.pumps_app_update() for viz in sim.visualizers): + return + try: + ensure_isaac_rtx_render_update() + except (ImportError, AttributeError) as exc: + logger.debug("[isaac_rtx] Skipping Kit app-loop pump in render() (non-Kit env): %s", exc) + except Exception as exc: + logger.warning("[isaac_rtx] Kit app-loop pump failed in render(): %s", exc) diff --git a/source/isaaclab_physx/isaaclab_physx/renderers/kit_viewport_utils.py b/source/isaaclab_physx/isaaclab_physx/renderers/kit_viewport_utils.py new file mode 100644 index 00000000000..4eaff041c41 --- /dev/null +++ b/source/isaaclab_physx/isaaclab_physx/renderers/kit_viewport_utils.py @@ -0,0 +1,33 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Kit / Omniverse viewport helpers (Isaac Sim specific). + +These live in :mod:`isaaclab_physx` so :class:`~isaaclab.sim.SimulationContext` stays +backend-agnostic. +""" + +from __future__ import annotations + +import logging + +logger = logging.getLogger(__name__) + + +def set_kit_renderer_camera_view( + 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 the 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("[kit_viewport] Renderer camera update skipped: %s", exc) diff --git a/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualizer.py b/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualizer.py index 6b1b5c2077d..36ec775325e 100644 --- a/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualizer.py +++ b/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualizer.py @@ -13,6 +13,7 @@ from pxr import UsdGeom +from isaaclab.app.settings_manager import get_settings_manager from isaaclab.visualizers.base_visualizer import BaseVisualizer from .kit_visualizer_cfg import KitVisualizerCfg @@ -81,9 +82,12 @@ 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), - ("camera_source", self.cfg.camera_source), + ("eye", self.cfg.eye), + ("lookat", self.cfg.lookat), + ("cam_source", self.cfg.cam_source), + ("visualizer_camera_prim_path", self.cfg.visualizer_camera_prim_path), + ("focal_length", self.cfg.focal_length), + ("enable_visualizer_cam", self.cfg.enable_visualizer_cam), ("num_visualized_envs", num_visualized_envs), ("create_viewport", self.cfg.create_viewport), ("headless", self._runtime_headless), @@ -105,12 +109,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. + # Keep app pumping for viewport/UI updates only; physics is owned by SimulationContext. + # Disable playSimulations around app.update() so Kit does not advance its own physics here. settings = get_settings_manager() settings.set_bool("/app/player/playSimulations", False) app.update() @@ -150,8 +152,6 @@ def is_running(self) -> bool: def is_training_paused(self) -> bool: """Return whether simulation play flag is paused in Kit settings.""" try: - from isaaclab.app.settings_manager import get_settings_manager - settings = get_settings_manager() play_flag = settings.get("/app/player/playSimulations") return play_flag is False @@ -186,6 +186,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 ---------------------------------------------------------------- @@ -228,9 +231,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" 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, @@ -250,7 +261,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() @@ -259,18 +269,20 @@ 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._set_viewport_camera(self.cfg.camera_position, self.cfg.camera_target) 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.""" @@ -304,12 +316,19 @@ 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(): UsdGeom.Camera.Define(usd_stage, camera_path) + camera_prim = usd_stage.GetPrimAtPath(camera_path) + + camera_geom = UsdGeom.Camera(camera_prim) + if camera_geom: + camera_geom.GetFocalLengthAttr().Set(float(self.cfg.focal_length)) if self._viewport_api: self._viewport_api.set_active_camera(camera_path) @@ -319,8 +338,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 @@ -328,10 +345,14 @@ 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" - - isaacsim_viewports.set_camera_view( - eye=list(position), target=list(target), camera_prim_path=camera_path, viewport_api=self._viewport_api - ) + 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) + + def _apply_cfg_camera_pose_if_configured(self) -> None: + """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: """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 88112a6f20b..31b0f7e2646 100644 --- a/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualizer_cfg.py +++ b/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualizer_cfg.py @@ -16,12 +16,25 @@ class KitVisualizerCfg(VisualizerCfg): visualizer_type: str = "kit" """Type identifier for Kit visualizer.""" - viewport_name: str | None = "Visualizer Viewport" - """Viewport name to use. If None, uses active viewport.""" + 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.""" + + focal_length: float = 12.0 + """Focal length in millimeters applied to the dedicated visualizer camera.""" + + 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 + 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 9ffeb062065..72172b1ecf7 100644 --- a/source/isaaclab_visualizers/isaaclab_visualizers/newton/newton_visualizer.py +++ b/source/isaaclab_visualizers/isaaclab_visualizers/newton/newton_visualizer.py @@ -56,7 +56,7 @@ def __init__( self._fallback_draw_controls = True def is_training_paused(self) -> bool: - """Return whether training is paused by viewer controls.""" + """Return whether simulation is paused by viewer controls.""" return self._paused_training def is_rendering_paused(self) -> bool: @@ -68,7 +68,7 @@ def _render_training_controls(self, imgui): imgui.separator() imgui.text("IsaacLab Controls") - pause_label = "Resume Training" if self._paused_training else "Pause Training" + pause_label = "Resume Simulation" if self._paused_training else "Pause Simulation" if imgui.button(pause_label): self._paused_training = not self._paused_training @@ -110,7 +110,7 @@ def _render_ui(self): imgui.set_next_window_pos(imgui.ImVec2(320, 10)) flags = 0 - if imgui.begin("Training Controls", flags=flags): + if imgui.begin("Simulation Controls", flags=flags): self._render_training_controls(imgui) imgui.end() return None @@ -292,29 +292,27 @@ def initialize(self, scene_data_provider: BaseSceneDataProvider) -> None: self._model = scene_data_provider.get_newton_model() self._state = scene_data_provider.get_newton_state(self._env_ids) - try: - self._viewer = NewtonViewerGL( - width=self.cfg.window_width, - height=self.cfg.window_height, - headless=self.cfg.headless, - metadata=metadata, - update_frequency=self.cfg.update_frequency, - ) - except Exception as exc: - if not self.cfg.headless: - raise - self._viewer = None - self._headless_no_viewer = True - logger.info( - "[NewtonVisualizer] Headless fallback enabled (ViewerGL unavailable in this environment): %s", - exc, - ) + # Use pyglet's EGL headless backend when requested. Must run before the first + # ``pyglet.window`` import so ``Window`` resolves to :class:`~pyglet.window.headless.HeadlessWindow`. + if self.cfg.headless: + import pyglet + + pyglet.options["headless"] = True + + self._viewer = NewtonViewerGL( + width=self.cfg.window_width, + height=self.cfg.window_height, + headless=self.cfg.headless, + metadata=metadata, + update_frequency=self.cfg.update_frequency, + ) if self._viewer is not 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() + self._apply_camera_pose(initial_pose) self._viewer.up_axis = 2 # Z-up self._viewer.scaling = 1.0 @@ -342,13 +340,11 @@ def initialize(self, scene_data_provider: BaseSceneDataProvider) -> None: title="NewtonVisualizer Configuration", rows=[ ( - "camera_position", - tuple(float(x) for x in self._viewer.camera.pos) - if self._viewer is not None - else self.cfg.camera_position, + "eye", + tuple(float(x) for x in self._viewer.camera.pos) if self._viewer is not None else self.cfg.eye, ), - ("camera_target", self._last_camera_pose[1] if self._last_camera_pose else self.cfg.camera_target), - ("camera_source", self.cfg.camera_source), + ("lookat", self._last_camera_pose[1] if self._last_camera_pose else self.cfg.lookat), + ("cam_source", self.cfg.cam_source), ("num_visualized_envs", num_visualized_envs), ("headless", self.cfg.headless), ], @@ -372,7 +368,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) @@ -437,15 +433,15 @@ def _resolve_initial_camera_pose(self) -> tuple[tuple[float, float, float], tupl Returns: 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.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. @@ -469,7 +465,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 ab2ed723223..531b067104c 100644 --- a/source/isaaclab_visualizers/isaaclab_visualizers/rerun/rerun_visualizer.py +++ b/source/isaaclab_visualizers/isaaclab_visualizers/rerun/rerun_visualizer.py @@ -188,7 +188,8 @@ 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() + self._apply_camera_pose(initial_pose) self._viewer.up_axis = 2 self._viewer.scaling = 1.0 self._viewer._paused = False @@ -198,9 +199,9 @@ 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), - ("camera_source", self.cfg.camera_source), + ("eye", self.cfg.eye), + ("lookat", self.cfg.lookat), + ("cam_source", self.cfg.cam_source), ("num_visualized_envs", num_visualized_envs), ("endpoint", f"http://{viewer_host}:{web_port}"), ("viewer_url", viewer_url), @@ -227,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,11 +276,15 @@ def is_running(self) -> bool: 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 - return self.cfg.camera_position, self.cfg.camera_target + 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: """Apply camera pose to rerun's 3D view controls. @@ -307,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 c20bfcd85a9..d6606403bba 100644 --- a/source/isaaclab_visualizers/isaaclab_visualizers/viser/viser_visualizer.py +++ b/source/isaaclab_visualizers/isaaclab_visualizers/viser/viser_visualizer.py @@ -162,9 +162,9 @@ 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), - ("camera_source", self.cfg.camera_source), + ("eye", self.cfg.eye), + ("lookat", self.cfg.lookat), + ("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() @@ -259,7 +259,8 @@ 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() + self._set_viser_camera_view(initial_pose) self._sim_time = 0.0 def _close_viewer(self, finalize_viser: bool = False) -> None: @@ -277,15 +278,15 @@ def _close_viewer(self, finalize_viser: bool = False) -> 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.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. @@ -341,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: diff --git a/source/isaaclab_visualizers/test/test_visualizer_cartpole_integration.py b/source/isaaclab_visualizers/test/test_visualizer_cartpole_integration.py new file mode 100644 index 00000000000..d008190a38f --- /dev/null +++ b/source/isaaclab_visualizers/test/test_visualizer_cartpole_integration.py @@ -0,0 +1,584 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Integration tests: Cartpole + visualizers, non-black frames, and log hygiene. + +Visualizer packages use ``logging.getLogger(__name__)``, so loggers are named like +``isaaclab_visualizers.kit.kit_visualizer`` and ``isaaclab.visualizers.base_visualizer``. +:class:`~isaaclab.sim.simulation_context.SimulationContext` uses +``logging.getLogger(__name__)`` → ``isaaclab.sim.simulation_context``. + +We filter :class:`~pytest.LogCaptureFixture` records with :data:`_VIS_LOGGER_PREFIXES` +so only those namespaces count (not Omniverse, PhysX, or unrelated warnings). + +Set :data:`ASSERT_VISUALIZER_WARNINGS` to ``True`` locally or in CI if you want tests to +fail on WARNING-level records from those loggers; by default only ERROR+ fails. +""" + +from __future__ import annotations + +# Pyglet must use HeadlessWindow (EGL) before ``pyglet.window`` is imported so Newton +# ViewerGL can construct without an X11 display (matches ``headless=True`` on NewtonVisualizerCfg). +import pyglet + +pyglet.options["headless"] = True + +from isaaclab.app import AppLauncher + +# launch Kit app +simulation_app = AppLauncher(headless=True, enable_cameras=True).app + +import contextlib +import copy +import logging +import socket + +import numpy as np +import pytest +import torch +import warp as wp +from isaaclab_visualizers.kit import KitVisualizer, KitVisualizerCfg +from isaaclab_visualizers.newton import NewtonVisualizer, NewtonVisualizerCfg +from isaaclab_visualizers.rerun import RerunVisualizer, RerunVisualizerCfg +from isaaclab_visualizers.viser import ViserVisualizer, ViserVisualizerCfg + +import isaaclab.sim as sim_utils +from isaaclab.sim import SimulationContext + +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 + +# When True, tests also fail on WARNING-level records from visualizer-related loggers. +ASSERT_VISUALIZER_WARNINGS = False + +_MAX_NON_BLACK_STEPS = 8 +"""Steps for tiled camera / Rerun / Viser smoke tests (early exit ok when non-black).""" + +_CARTPOLE_INTEGRATION_NUM_ENVS = 1 +"""Vectorized env count for cartpole + visualizer integration tests.""" + +_CARTPOLE_INTEGRATION_VISUALIZER_EYE: tuple[float, float, float] = (3.0, 3.0, 3.0) +"""Passed to :class:`~isaaclab.visualizers.visualizer_cfg.VisualizerCfg` subclasses (``eye``).""" + +_CARTPOLE_INTEGRATION_VISUALIZER_LOOKAT: tuple[float, float, float] = (-4.0, -4.0, 0.0) +"""Passed to visualizer cfgs (``lookat``); also applied to :class:`~isaaclab.envs.common.ViewerCfg` for the env.""" + +# Resolution overrides for this test module (cartpole preset defaults: tiled camera 100×100; Kit helper was 320×240). +_CARTPOLE_KIT_INTEGRATION_RENDER_RESOLUTION: tuple[int, int] = (600, 600) +"""Kit: Replicator ``render_product`` (width, height) for viewport RGB in the motion check.""" + +_CARTPOLE_NEWTON_INTEGRATION_WINDOW_SIZE: tuple[int, int] = (600, 600) +"""Newton: ``NewtonVisualizerCfg`` framebuffer (window_width × window_height) for ``get_frame()``.""" + +_CARTPOLE_TILED_CAMERA_INTEGRATION_WH: tuple[int, int] = (600, 600) +"""Tiled camera per-env tile width/height (preset default is 100×100); keeps ``observation_space`` consistent.""" + +_VIS_FRAME_TEST_STEPS = 60 +"""Steps for Kit / Newton frame capture: no early exit.""" + +# Motion check compares the 2nd vs last captured frame (e.g. 2nd vs 60th when *_STEPS* is 60). +_MOTION_FRAME_EARLY_IDX = 1 +"""0-based index of the *early* frame (2nd capture).""" + +_MOTION_FRAME_LATE_IDX = _VIS_FRAME_TEST_STEPS - 1 +"""0-based index of the *late* frame (e.g. 60th capture when :data:`_VIS_FRAME_TEST_STEPS` is 60).""" + +# Early vs late frame motion: void background stays similar; only count *strongly* differing pixels. +_FRAME_MOTION_CHANNEL_DIFF_THRESHOLD = 50 +"""A pixel counts as differing if max(|ΔR|, |ΔG|, |ΔB|) >= this (0–255 space).""" + +_FRAME_MOTION_MIN_DIFFERING_PIXELS = 100 +"""Minimum number of such pixels between early and late frames (stale/frozen viz should be near zero).""" + +_VIS_LOGGER_PREFIXES = ( + "isaaclab.visualizers", + "isaaclab_visualizers", + "isaaclab.sim.simulation_context", +) + + +def _logger_name_matches_visualizer_scope(logger_name: str) -> bool: + """Return True if *logger_name* is a visualizer / SimulationContext visualizer path.""" + return any(logger_name.startswith(prefix) for prefix in _VIS_LOGGER_PREFIXES) + + +def _assert_no_visualizer_log_issues(caplog: pytest.LogCaptureFixture, *, fail_on_warnings: bool | None = None) -> None: + """Fail if captured records include ERROR/CRITICAL (always) or WARNING (if *fail_on_warnings*). + + *fail_on_warnings* defaults to :data:`ASSERT_VISUALIZER_WARNINGS`. + """ + if fail_on_warnings is None: + fail_on_warnings = ASSERT_VISUALIZER_WARNINGS + + error_logs = [ + r for r in caplog.records if r.levelno >= logging.ERROR and _logger_name_matches_visualizer_scope(r.name) + ] + assert not error_logs, "Visualizer-related error logs: " + "; ".join( + f"{r.name}: {r.getMessage()}" for r in error_logs + ) + + if fail_on_warnings: + warning_logs = [ + r for r in caplog.records if r.levelno == logging.WARNING and _logger_name_matches_visualizer_scope(r.name) + ] + assert not warning_logs, "Visualizer-related warning logs: " + "; ".join( + f"{r.name}: {r.getMessage()}" for r in warning_logs + ) + + +def _configure_sim_for_visualizer_test(env: CartpoleCameraEnv) -> None: + """Settings used by the previous smoke tests; keep RTX sensors enabled for camera paths.""" + env.sim.set_setting("/isaaclab/render/rtx_sensors", True) + env.sim._app_control_on_stop_handle = None # type: ignore[attr-defined] + + +def _find_free_tcp_port(host: str = "127.0.0.1") -> int: + """Ask OS for a currently free local TCP port.""" + with socket.socket(socket.AF_INET, socket.SOCK_STREAM) as sock: + sock.bind((host, 0)) + return int(sock.getsockname()[1]) + + +def _allocate_rerun_test_ports(host: str = "127.0.0.1") -> tuple[int, int]: + """Allocate distinct free ports for rerun web and gRPC endpoints.""" + grpc_port = _find_free_tcp_port(host) + web_port = _find_free_tcp_port(host) + while web_port == grpc_port: + web_port = _find_free_tcp_port(host) + return web_port, grpc_port + + +def _cartpole_integration_visualizer_camera_kwargs() -> dict[str, tuple[float, float, float]]: + """Eye/lookat for all :class:`~isaaclab.visualizers.visualizer_cfg.VisualizerCfg` subclasses in these tests.""" + return { + "eye": _CARTPOLE_INTEGRATION_VISUALIZER_EYE, + "lookat": _CARTPOLE_INTEGRATION_VISUALIZER_LOOKAT, + } + + +def _get_visualizer_cfg(visualizer_kind: str): + """Return (visualizer_cfg, expected_visualizer_cls) for the given visualizer kind.""" + cam = _cartpole_integration_visualizer_camera_kwargs() + if visualizer_kind == "newton": + __import__("newton") + nw, nh = _CARTPOLE_NEWTON_INTEGRATION_WINDOW_SIZE + return NewtonVisualizerCfg(headless=True, window_width=nw, window_height=nh, **cam), NewtonVisualizer + if visualizer_kind == "viser": + __import__("newton") + __import__("viser") + port = _find_free_tcp_port(host="127.0.0.1") + return ViserVisualizerCfg(open_browser=False, port=port, **cam), ViserVisualizer + if visualizer_kind == "rerun": + __import__("newton") + __import__("rerun") + web_port, grpc_port = _allocate_rerun_test_ports(host="127.0.0.1") + return ( + RerunVisualizerCfg( + bind_address="127.0.0.1", + open_browser=False, + web_port=web_port, + grpc_port=grpc_port, + **cam, + ), + RerunVisualizer, + ) + return KitVisualizerCfg(**cam), KitVisualizer + + +def _get_physics_cfg(backend_kind: str): + """Return physics config and expected backend substring for the given backend kind.""" + if backend_kind == "physx": + __import__("isaaclab_physx") + preset = CartpolePhysicsCfg() + physics_cfg = getattr(preset, "physx", None) + if physics_cfg is None: + from isaaclab_physx.physics import PhysxCfg + + physics_cfg = PhysxCfg() + return physics_cfg, "physx" + if backend_kind == "newton": + __import__("newton") + __import__("isaaclab_newton") + preset = CartpolePhysicsCfg() + physics_cfg = getattr(preset, "newton", None) + if physics_cfg is None: + from isaaclab_newton.physics import MJWarpSolverCfg, NewtonCfg + + physics_cfg = NewtonCfg( + solver_cfg=MJWarpSolverCfg( + njmax=5, + nconmax=3, + cone="pyramidal", + impratio=1, + integrator="implicitfast", + ), + num_substeps=1, + debug_mode=False, + use_cuda_graph=True, + ) + return physics_cfg, "newton" + 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 _frame_to_numpy(frame) -> np.ndarray: + """Convert viewer ``get_frame()`` output (numpy, torch, or Warp array) to host ``numpy.ndarray``. + + ``np.asarray(wp.array)`` is unsafe: NumPy can trigger Warp indexing that raises at dimension edges. + """ + if isinstance(frame, np.ndarray): + return frame + if isinstance(frame, torch.Tensor): + return frame.detach().cpu().numpy() + if isinstance(frame, wp.array): + return wp.to_torch(frame).detach().cpu().numpy() + return np.asarray(frame) + + +def _assert_non_black_frame_array(frame) -> None: + """Assert viewer-captured frame has visible, non-black content.""" + frame_arr = _frame_to_numpy(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 _frame_rgb_255_space(frame) -> np.ndarray: + """Return HxWx3 float in ~0–255 space for per-channel differencing.""" + arr = _frame_to_numpy(frame) + if arr.ndim == 2: + rgb = np.stack([arr, arr, arr], axis=-1) + else: + rgb = arr[..., :3] + rgb = np.asarray(rgb, dtype=np.float64) + # Normalized HDR buffers: scale so threshold matches (0,255) semantics. + if rgb.size > 0 and float(np.nanmax(rgb)) <= 1.0 + 1e-6: + rgb = rgb * 255.0 + return rgb + + +def _count_significantly_differing_pixels( + frame_a, + frame_b, + *, + channel_diff_threshold: float = _FRAME_MOTION_CHANNEL_DIFF_THRESHOLD, +) -> int: + """Count pixels where max(|ΔR|, |ΔG|, |ΔB|) >= *channel_diff_threshold* (0–255 space).""" + a = _frame_rgb_255_space(frame_a) + b = _frame_rgb_255_space(frame_b) + assert a.shape == b.shape, f"Frame shape mismatch for motion check: {a.shape} vs {b.shape}." + per_pixel_max = np.max(np.abs(a - b), axis=-1) + return int(np.count_nonzero(per_pixel_max >= channel_diff_threshold)) + + +def _assert_early_and_late_motion_frames_differ( + frames: list, + *, + channel_diff_threshold: float = _FRAME_MOTION_CHANNEL_DIFF_THRESHOLD, + min_differing_pixels: int = _FRAME_MOTION_MIN_DIFFERING_PIXELS, +) -> None: + """Fail if early vs late frames lack enough strongly differing pixels (stale/frozen bodies). + + Compares :data:`_MOTION_FRAME_EARLY_IDX` vs :data:`_MOTION_FRAME_LATE_IDX` (e.g. 2nd vs 60th capture). + + Voids/background stay near-identical; we only count pixels that change by at least + *channel_diff_threshold* on some channel (0–255). + """ + assert len(frames) >= _VIS_FRAME_TEST_STEPS, ( + f"Need at least {_VIS_FRAME_TEST_STEPS} frames for motion check, got {len(frames)}." + ) + i_early = _MOTION_FRAME_EARLY_IDX + i_late = _MOTION_FRAME_LATE_IDX + early_1 = i_early + 1 + late_1 = i_late + 1 + n_diff = _count_significantly_differing_pixels( + frames[i_early], frames[i_late], channel_diff_threshold=channel_diff_threshold + ) + assert n_diff >= min_differing_pixels, ( + f"Viewport captures #{early_1} and #{late_1} have too few strongly differing pixels " + f"({n_diff} < {min_differing_pixels}; threshold per channel={channel_diff_threshold} in 0–255 space). " + "Possible frozen or stale robot visualization." + ) + + +def _step_until_non_black_camera(env, actions: torch.Tensor, *, max_steps: int = _MAX_NON_BLACK_STEPS) -> None: + """Step env until the env's tiled camera RGB tensor 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 + _assert_non_black_tensor(last_rgb) + + +def _run_newton_viewer_frame_motion_test( + viewer, + *, + step_hook, + physics_kind: str, + viz_kind: str = "newton", +) -> None: + """Exactly ``_VIS_FRAME_TEST_STEPS`` sim steps; last frame non-black; early vs late motion check.""" + frames: list = [] + for _ in range(_VIS_FRAME_TEST_STEPS): + step_hook() + frames.append(viewer.get_frame()) + _assert_non_black_frame_array(frames[-1]) + _assert_early_and_late_motion_frames_differ(frames) + + +def _step_env_without_frame_check(env, actions: torch.Tensor, *, max_steps: int = _MAX_NON_BLACK_STEPS) -> None: + """Step the env to exercise visualizers that do not implement ``get_frame`` (e.g. Rerun, Viser).""" + for _ in range(max_steps): + env.step(action=actions) + + +def _build_rgb_annotator_for_camera( + camera_path: str, + *, + resolution: tuple[int, int] | None = None, +): + """Create CPU RGB annotator attached to a camera render product.""" + import omni.replicator.core as rep + + if resolution is None: + resolution = _CARTPOLE_KIT_INTEGRATION_RENDER_RESOLUTION + 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 _run_kit_viewport_frame_motion_test( + env, + kit_visualizer: KitVisualizer, + *, + physics_kind: str, + viz_kind: str = "kit", +) -> None: + """Exactly ``_VIS_FRAME_TEST_STEPS`` env steps; last Replicator frame non-black; early vs late motion check.""" + camera_path = getattr(kit_visualizer, "_controlled_camera_path", None) + assert camera_path, "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) + frames: list = [] + for _ in range(_VIS_FRAME_TEST_STEPS): + env.step(action=actions) + rgb_data = annotator.get_data() + frames.append(_annotator_rgb_to_numpy(rgb_data)) + _assert_non_black_frame_array(frames[-1]) + _assert_early_and_late_motion_frames_differ(frames) + 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() + 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 = _CARTPOLE_INTEGRATION_NUM_ENVS + env_cfg.viewer.eye = _CARTPOLE_INTEGRATION_VISUALIZER_EYE + env_cfg.viewer.lookat = _CARTPOLE_INTEGRATION_VISUALIZER_LOOKAT + tw, th = _CARTPOLE_TILED_CAMERA_INTEGRATION_WH + env_cfg.tiled_camera.width = tw + env_cfg.tiled_camera.height = th + if isinstance(env_cfg.observation_space, list) and len(env_cfg.observation_space) >= 3: + env_cfg.observation_space = [th, tw, env_cfg.observation_space[2]] + 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) + + +@pytest.mark.isaacsim_ci +@pytest.mark.parametrize( + "backend_kind", + [ + "physx", + pytest.param( + "newton", + marks=pytest.mark.skip( + reason=( + "TODO: Kit visualizer + Newton physics + Isaac RTX tiled camera can hit CUDA illegal access " + "or bad GPU state. Repro: rl_games train Isaac-Cartpole-Camera-Presets-Direct-v0 " + "--enable_cameras presets=newton --viz kit. Re-enable when fixed." + ) + ), + ), + ], +) +def test_kit_visualizer_non_black_viewport_frame(backend_kind: str, caplog: pytest.LogCaptureFixture) -> None: + """Kit viewport: full motion steps, last frame non-black; 2nd vs last capture differ; clean logs.""" + env = None + try: + sim_utils.create_new_stage() + env = _make_cartpole_camera_env(visualizer_kind="kit", backend_kind=backend_kind) + _configure_sim_for_visualizer_test(env) + with caplog.at_level(logging.WARNING): + env.reset() + kit_visualizers = [viz for viz in env.sim.visualizers if isinstance(viz, KitVisualizer)] + assert kit_visualizers, "Expected an initialized Kit visualizer." + _run_kit_viewport_frame_motion_test(env, kit_visualizers[0], physics_kind=backend_kind) + _assert_no_visualizer_log_issues(caplog) + 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_cartpole_tiled_camera_rgb_non_black(backend_kind: str, caplog: pytest.LogCaptureFixture) -> None: + """Tiled camera RGB is not all-black; no visualizer ERROR (optional WARNING).""" + env = None + try: + sim_utils.create_new_stage() + env = _make_cartpole_camera_env(visualizer_kind="newton", backend_kind=backend_kind) + _configure_sim_for_visualizer_test(env) + with caplog.at_level(logging.WARNING): + 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) + _assert_no_visualizer_log_issues(caplog) + 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, caplog: pytest.LogCaptureFixture) -> None: + """Newton GL ``get_frame``: full motion steps, last frame non-black; 2nd vs last capture differ; clean logs.""" + env = None + try: + sim_utils.create_new_stage() + env = _make_cartpole_camera_env(visualizer_kind="newton", backend_kind=backend_kind) + _configure_sim_for_visualizer_test(env) + with caplog.at_level(logging.WARNING): + env.reset() + actions = torch.zeros((env.num_envs, env.action_space.shape[-1]), device=env.device) + 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." + + def _step_env() -> None: + env.step(action=actions) + + _run_newton_viewer_frame_motion_test(viewer, step_hook=_step_env, physics_kind=backend_kind) + _assert_no_visualizer_log_issues(caplog) + 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_rerun_visualizer_non_black_viewer_frame(backend_kind: str, caplog: pytest.LogCaptureFixture) -> None: + """Rerun visualizer initializes; env steps exercise it; no visualizer ERROR (optional WARNING). + + Rerun's viewer does not expose ``get_frame``, so we do not assert on a non-black frame. + """ + env = None + try: + sim_utils.create_new_stage() + env = _make_cartpole_camera_env(visualizer_kind="rerun", backend_kind=backend_kind) + _configure_sim_for_visualizer_test(env) + with caplog.at_level(logging.WARNING): + env.reset() + actions = torch.zeros((env.num_envs, env.action_space.shape[-1]), device=env.device) + rerun_visualizers = [viz for viz in env.sim.visualizers if isinstance(viz, RerunVisualizer)] + assert rerun_visualizers, "Expected an initialized Rerun visualizer." + assert getattr(rerun_visualizers[0], "_viewer", None) is not None, "Rerun viewer was not created." + _step_env_without_frame_check(env, actions, max_steps=_MAX_NON_BLACK_STEPS) + _assert_no_visualizer_log_issues(caplog) + 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_viser_visualizer_non_black_viewer_frame(backend_kind: str, caplog: pytest.LogCaptureFixture) -> None: + """Viser visualizer initializes; env steps exercise it; no visualizer ERROR (optional WARNING). + + Viser's Newton-backed viewer does not expose ``get_frame``, so we do not assert on a non-black frame. + """ + env = None + try: + sim_utils.create_new_stage() + env = _make_cartpole_camera_env(visualizer_kind="viser", backend_kind=backend_kind) + _configure_sim_for_visualizer_test(env) + with caplog.at_level(logging.WARNING): + env.reset() + actions = torch.zeros((env.num_envs, env.action_space.shape[-1]), device=env.device) + viser_visualizers = [viz for viz in env.sim.visualizers if isinstance(viz, ViserVisualizer)] + assert viser_visualizers, "Expected an initialized Viser visualizer." + assert getattr(viser_visualizers[0], "_viewer", None) is not None, "Viser viewer was not created." + _step_env_without_frame_check(env, actions, max_steps=_MAX_NON_BLACK_STEPS) + _assert_no_visualizer_log_issues(caplog) + finally: + if env is not None: + env.close() + else: + SimulationContext.clear_instance() + + +if __name__ == "__main__": + pytest.main([__file__, "-v", "--maxfail=1"]) diff --git a/source/isaaclab_visualizers/test/test_visualizer_smoke_logs.py b/source/isaaclab_visualizers/test/test_visualizer_smoke_logs.py deleted file mode 100644 index 22f620fb02a..00000000000 --- a/source/isaaclab_visualizers/test/test_visualizer_smoke_logs.py +++ /dev/null @@ -1,228 +0,0 @@ -# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). -# All rights reserved. -# -# SPDX-License-Identifier: BSD-3-Clause - -"""Smoke test visualizer stepping and error logging.""" - -from isaaclab.app import AppLauncher - -# launch Kit app -simulation_app = AppLauncher(headless=True, enable_cameras=True).app - -import logging -import socket - -import pytest -import torch -from isaaclab_visualizers.kit import KitVisualizer, KitVisualizerCfg -from isaaclab_visualizers.newton import NewtonVisualizer, NewtonVisualizerCfg -from isaaclab_visualizers.rerun import RerunVisualizer, RerunVisualizerCfg -from isaaclab_visualizers.viser import ViserVisualizer, ViserVisualizerCfg - -import isaaclab.sim as sim_utils -from isaaclab.envs import DirectRLEnv, DirectRLEnvCfg -from isaaclab.scene import InteractiveSceneCfg -from isaaclab.sim import SimulationCfg, SimulationContext -from isaaclab.utils import configclass - -from isaaclab_tasks.manager_based.classic.cartpole.cartpole_env_cfg import ( - CartpolePhysicsCfg, - CartpoleSceneCfg, -) - -# Set to False to only fail on visualizer errors; when True, also fail on warnings. -ASSERT_VISUALIZER_WARNINGS = True - -_SMOKE_STEPS = 4 -_VIS_LOGGER_PREFIXES = ( - "isaaclab.visualizers", - "isaaclab_visualizers", - "isaaclab.sim.simulation_context", -) - - -def _find_free_tcp_port(host: str = "127.0.0.1") -> int: - """Ask OS for a currently free local TCP port.""" - with socket.socket(socket.AF_INET, socket.SOCK_STREAM) as sock: - sock.bind((host, 0)) - return int(sock.getsockname()[1]) - - -def _allocate_rerun_test_ports(host: str = "127.0.0.1") -> tuple[int, int]: - """Allocate distinct free ports for rerun web and gRPC endpoints.""" - grpc_port = _find_free_tcp_port(host) - web_port = _find_free_tcp_port(host) - while web_port == grpc_port: - web_port = _find_free_tcp_port(host) - return web_port, grpc_port - - -@configclass -class _SmokeEnvCfg(DirectRLEnvCfg): - decimation: int = 2 - action_space: int = 0 - observation_space: int = 0 - episode_length_s: float = 5.0 - sim: SimulationCfg = SimulationCfg(dt=0.005, render_interval=2, visualizer_cfgs=KitVisualizerCfg()) - scene: InteractiveSceneCfg = InteractiveSceneCfg(num_envs=1, env_spacing=1.0) - - -class _SmokeEnv(DirectRLEnv): - def _pre_physics_step(self, actions): - return - - def _apply_action(self): - return - - def _get_observations(self): - return {} - - def _get_rewards(self): - return {} - - def _get_dones(self): - return torch.zeros(1, dtype=torch.bool), torch.zeros(1, dtype=torch.bool) - - -def _get_visualizer_cfg(visualizer_kind: str): - """Return (visualizer_cfg, expected_visualizer_cls) for the given visualizer kind.""" - if visualizer_kind == "newton": - __import__("newton") - return NewtonVisualizerCfg(headless=True), NewtonVisualizer - if visualizer_kind == "viser": - __import__("newton") - __import__("viser") - return ViserVisualizerCfg(open_browser=False), ViserVisualizer - if visualizer_kind == "rerun": - __import__("newton") - __import__("rerun") - web_port, grpc_port = _allocate_rerun_test_ports(host="127.0.0.1") - # Use dynamically allocated non-default ports in smoke tests to avoid collisions. - # TODO: Consider supporting cleanup/termination of stale rerun processes when ports are occupied. - return ( - RerunVisualizerCfg( - bind_address="127.0.0.1", - open_browser=False, - web_port=web_port, - grpc_port=grpc_port, - ), - RerunVisualizer, - ) - return KitVisualizerCfg(), KitVisualizer - - -def _get_physics_cfg(backend_kind: str): - """Return physics config and expected backend substring for the given backend kind. - - Uses cartpole preset instance so we work whether presets are class or instance attributes. - Fallback: build PhysxCfg/NewtonCfg in-test if preset does not expose that backend. - """ - if backend_kind == "physx": - __import__("isaaclab_physx") - preset = CartpolePhysicsCfg() - physics_cfg = getattr(preset, "physx", None) - if physics_cfg is None: - from isaaclab_physx.physics import PhysxCfg - - physics_cfg = PhysxCfg() - return physics_cfg, "physx" - if backend_kind == "newton": - __import__("newton") - __import__("isaaclab_newton") - preset = CartpolePhysicsCfg() - physics_cfg = getattr(preset, "newton", None) - if physics_cfg is None: - from isaaclab_newton.physics import MJWarpSolverCfg, NewtonCfg - - physics_cfg = NewtonCfg( - solver_cfg=MJWarpSolverCfg( - njmax=5, - nconmax=3, - cone="pyramidal", - impratio=1, - integrator="implicitfast", - ), - num_substeps=1, - debug_mode=False, - use_cuda_graph=True, - ) - return physics_cfg, "newton" - raise ValueError(f"Unknown backend: {backend_kind!r}") - - -def _resolve_case(visualizer_kind: str, backend_kind: str): - """Resolve (env_cfg, expected_visualizer_cls, expected_backend_substring) for one smoke test. - - Uses cartpole scene for all combinations (works with both PhysX and Newton). - """ - scene_cfg = CartpoleSceneCfg(num_envs=1, env_spacing=1.0) - viz_cfg, expected_viz_cls = _get_visualizer_cfg(visualizer_kind) - physics_cfg, expected_backend = _get_physics_cfg(backend_kind) - - cfg = _SmokeEnvCfg() - cfg.scene = scene_cfg - cfg.sim = SimulationCfg( - dt=0.005, - render_interval=2, - visualizer_cfgs=viz_cfg, - physics=physics_cfg, - ) - return cfg, expected_viz_cls, expected_backend - - -def _run_smoke_test(cfg, expected_visualizer_cls, expected_backend: str, caplog) -> None: - """Run smoke steps and assert no visualizer errors; optionally no warnings (see ASSERT_VISUALIZER_WARNINGS).""" - env = None - try: - sim_utils.create_new_stage() - env = _SmokeEnv(cfg=cfg) - backend_name = env.sim.physics_manager.__name__.lower() - assert expected_backend in backend_name, ( - f"Expected physics backend containing {expected_backend!r}, got {backend_name!r}" - ) - env.sim.set_setting("/isaaclab/render/rtx_sensors", True) - env.sim._app_control_on_stop_handle = None # type: ignore[attr-defined] - - actions = torch.zeros((env.num_envs, 0), device=env.device) - with caplog.at_level(logging.WARNING): - env.reset() - assert env.sim.visualizers - assert isinstance(env.sim.visualizers[0], expected_visualizer_cls) - for _ in range(_SMOKE_STEPS): - env.step(action=actions) - - # Always fail on errors - error_logs = [ - r for r in caplog.records if r.levelno >= logging.ERROR and r.name.startswith(_VIS_LOGGER_PREFIXES) - ] - assert not error_logs, "Visualizer emitted error logs during smoke stepping: " + "; ".join( - f"{r.name}: {r.message}" for r in error_logs - ) - - # Optionally fail on warnings - if ASSERT_VISUALIZER_WARNINGS: - warning_logs = [ - r for r in caplog.records if r.levelno >= logging.WARNING and r.name.startswith(_VIS_LOGGER_PREFIXES) - ] - assert not warning_logs, "Visualizer emitted warning logs during smoke stepping: " + "; ".join( - f"{r.name}: {r.message}" for r in warning_logs - ) - finally: - if env is not None: - env.close() - else: - SimulationContext.clear_instance() - - -@pytest.mark.isaacsim_ci -@pytest.mark.parametrize("visualizer_kind", ["kit", "newton", "rerun", "viser"]) -@pytest.mark.parametrize("backend_kind", ["physx", "newton"]) -def test_visualizer_backend_smoke(visualizer_kind: str, backend_kind: str, caplog): - """Smoke test each (visualizer, backend) pair; assert no errors (optionally no warnings).""" - cfg, expected_viz_cls, expected_backend = _resolve_case(visualizer_kind, backend_kind) - _run_smoke_test(cfg, expected_viz_cls, expected_backend, caplog) - - -if __name__ == "__main__": - pytest.main([__file__, "-v", "--maxfail=1"])