From d4dc70e548f6d6218cbee5e08ae0f4caf96a5224 Mon Sep 17 00:00:00 2001 From: mtrepte Date: Fri, 7 Nov 2025 19:11:23 -0800 Subject: [PATCH 01/24] init --- .../isaaclab/sim/_impl/newton_manager_cfg.py | 15 +- .../isaaclab/isaaclab/sim/simulation_cfg.py | 18 ++ .../isaaclab/sim/visualizers/__init__.py | 30 ++++ .../sim/visualizers/newton_visualizer_cfg.py | 132 +++++++++++++++ .../sim/visualizers/ov_visualizer_cfg.py | 160 ++++++++++++++++++ .../sim/visualizers/rerun_visualizer_cfg.py | 159 +++++++++++++++++ .../sim/visualizers/visualizer_cfg.py | 89 ++++++++++ 7 files changed, 593 insertions(+), 10 deletions(-) create mode 100644 source/isaaclab/isaaclab/sim/visualizers/__init__.py create mode 100644 source/isaaclab/isaaclab/sim/visualizers/newton_visualizer_cfg.py create mode 100644 source/isaaclab/isaaclab/sim/visualizers/ov_visualizer_cfg.py create mode 100644 source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer_cfg.py create mode 100644 source/isaaclab/isaaclab/sim/visualizers/visualizer_cfg.py diff --git a/source/isaaclab/isaaclab/sim/_impl/newton_manager_cfg.py b/source/isaaclab/isaaclab/sim/_impl/newton_manager_cfg.py index d827e28d645..02523192c0b 100644 --- a/source/isaaclab/isaaclab/sim/_impl/newton_manager_cfg.py +++ b/source/isaaclab/isaaclab/sim/_impl/newton_manager_cfg.py @@ -12,7 +12,11 @@ class NewtonCfg: """Configuration for Newton-related parameters. - These parameters are used to configure the Newton simulation. + These parameters are used to configure the Newton physics simulation. + + Note: + Visualizer-related settings have been moved to NewtonVisualizerCfg in + isaaclab.sim.visualizers.newton_visualizer_cfg. """ num_substeps: int = 1 @@ -27,13 +31,4 @@ class NewtonCfg: If set to False, the simulation performance will be severely degraded. """ - newton_viewer_update_frequency: int = 1 - """Frequency of updates to the Newton viewer.""" - - newton_viewer_camera_pos: tuple[float, float, float] = (10.0, 0.0, 3.0) - """Position of the camera in the Newton viewer.""" - - visualizer_train_mode: bool = True - """Whether the visualizer is in training mode (True) or play mode (False).""" - solver_cfg: NewtonSolverCfg = MJWarpSolverCfg() diff --git a/source/isaaclab/isaaclab/sim/simulation_cfg.py b/source/isaaclab/isaaclab/sim/simulation_cfg.py index bea86d4150c..f6f2dfd5957 100644 --- a/source/isaaclab/isaaclab/sim/simulation_cfg.py +++ b/source/isaaclab/isaaclab/sim/simulation_cfg.py @@ -15,6 +15,7 @@ from ._impl.newton_manager_cfg import NewtonCfg from .spawners.materials import RigidBodyMaterialCfg +from .visualizers import VisualizerCfg @configclass @@ -203,6 +204,23 @@ class SimulationCfg: renderer is also enabled, both will be called. """ + visualizer: VisualizerCfg | None = None + """Visualizer settings. Default is None (no visualizer). + + To enable a visualizer, set this to one of the visualizer configuration classes: + - NewtonVisualizerCfg: Lightweight OpenGL-based visualizer + - OVVisualizerCfg: Omniverse-based high-fidelity visualizer + - RerunVisualizerCfg: Web-based Rerun visualizer + + Example: + from isaaclab.sim.visualizers import NewtonVisualizerCfg + cfg = SimulationCfg(visualizer=NewtonVisualizerCfg(enabled=True)) + + Note: + This replaces the previous enable_newton_rendering flag and provides a unified + interface for all visualizer backends. + """ + create_stage_in_memory: bool = False """If stage is first created in memory. Default is False. diff --git a/source/isaaclab/isaaclab/sim/visualizers/__init__.py b/source/isaaclab/isaaclab/sim/visualizers/__init__.py new file mode 100644 index 00000000000..64a9dcf7f51 --- /dev/null +++ b/source/isaaclab/isaaclab/sim/visualizers/__init__.py @@ -0,0 +1,30 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Sub-package for visualizer configurations. + +This sub-package contains configuration classes for different visualizer backends +that can be used with Isaac Lab. The visualizers are used for debug visualization +and monitoring of the simulation, separate from rendering for sensors. + +Supported visualizers: +- Newton OpenGL Visualizer: Lightweight OpenGL-based visualizer +- Omniverse Visualizer: High-fidelity Omniverse-based visualizer +- Rerun Visualizer: Web-based visualizer using the rerun library +""" + +from .visualizer_cfg import VisualizerCfg +from .newton_visualizer_cfg import NewtonVisualizerCfg +from .ov_visualizer_cfg import OVVisualizerCfg +from .rerun_visualizer_cfg import RerunVisualizerCfg + +__all__ = [ + "VisualizerCfg", + "NewtonVisualizerCfg", + "OVVisualizerCfg", + "RerunVisualizerCfg", +] + + diff --git a/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer_cfg.py b/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer_cfg.py new file mode 100644 index 00000000000..e9304f9eca9 --- /dev/null +++ b/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer_cfg.py @@ -0,0 +1,132 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Configuration for Newton OpenGL Visualizer.""" + +from typing import Literal + +from isaaclab.utils import configclass + +from .visualizer_cfg import VisualizerCfg + + +@configclass +class NewtonVisualizerCfg(VisualizerCfg): + """Configuration for Newton OpenGL Visualizer. + + The Newton OpenGL Visualizer is a lightweight, fast visualizer built on OpenGL. + It is designed for interactive real-time visualization of simulations with minimal + performance overhead. It requires pyglet (version >= 2.1.6) and imgui_bundle + (version >= 1.92.0) to be installed. + + Features: + - Real-time 3D visualization + - Interactive camera controls + - Debug visualization (contacts, joints, springs, COM) + - Training controls (pause training, pause rendering, update frequency) + - Lightweight and fast + + Note: + The Newton Visualizer currently only supports visualization of collision shapes, + not visual shapes. + """ + + # Override defaults for Newton visualizer + camera_position: tuple[float, float, float] = (10.0, 0.0, 3.0) + """Initial position of the camera. Default is (10.0, 0.0, 3.0).""" + + window_width: int = 1920 + """Width of the visualizer window in pixels. Default is 1920.""" + + window_height: int = 1080 + """Height of the visualizer window in pixels. Default is 1080.""" + + # Newton-specific settings + fps: int = 60 + """Target frames per second for the visualizer. Default is 60.""" + + show_joints: bool = True + """Whether to show joint visualizations. Default is True.""" + + show_contacts: bool = False + """Whether to show contact visualizations. Default is False.""" + + show_springs: bool = False + """Whether to show spring visualizations. Default is False.""" + + show_com: bool = False + """Whether to show center of mass visualizations. Default is False.""" + + show_ui: bool = True + """Whether to show the UI sidebar. Default is True. + + The UI can be toggled with the 'H' key during runtime. + """ + + enable_shadows: bool = True + """Whether to enable shadow rendering. Default is True.""" + + enable_sky: bool = True + """Whether to enable sky rendering. Default is True.""" + + enable_wireframe: bool = False + """Whether to enable wireframe rendering mode. Default is False.""" + + up_axis: Literal["X", "Y", "Z"] = "Z" + """The up axis for the visualizer. Default is "Z". + + This should typically match the up axis of your simulation environment. + """ + + fov: float = 60.0 + """Field of view for the camera in degrees. Default is 60.0.""" + + near_plane: float = 0.1 + """Near clipping plane distance for the camera. Default is 0.1.""" + + far_plane: float = 1000.0 + """Far clipping plane distance for the camera. Default is 1000.0.""" + + background_color: tuple[float, float, float] = (0.53, 0.81, 0.92) + """Background color (sky color) as RGB values in range [0, 1]. + Default is (0.53, 0.81, 0.92) (light blue).""" + + ground_color: tuple[float, float, float] = (0.18, 0.20, 0.25) + """Ground color as RGB values in range [0, 1]. + Default is (0.18, 0.20, 0.25) (dark gray).""" + + light_color: tuple[float, float, float] = (1.0, 1.0, 1.0) + """Light color as RGB values in range [0, 1]. Default is (1.0, 1.0, 1.0) (white).""" + + enable_pause_training: bool = True + """Whether to enable the pause training button in the UI. Default is True. + + When enabled, users can pause the simulation/training while keeping the + visualizer running, which is useful for debugging. + """ + + enable_pause_rendering: bool = True + """Whether to enable the pause rendering button in the UI. Default is True. + + When enabled, users can pause rendering while keeping simulation/training + running, which can improve training performance. + """ + + show_training_controls: bool = True + """Whether to show IsaacLab-specific training controls in the UI. Default is True. + + This includes controls for pausing training, pausing rendering, and adjusting + the visualizer update frequency. + """ + + render_mode: Literal["rgb", "depth", "collision"] = "rgb" + """Rendering mode for the visualizer. Default is "rgb". + + - "rgb": Standard RGB rendering + - "depth": Depth visualization + - "collision": Show collision shapes only + """ + + diff --git a/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer_cfg.py b/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer_cfg.py new file mode 100644 index 00000000000..e67cc47b116 --- /dev/null +++ b/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer_cfg.py @@ -0,0 +1,160 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Configuration for Omniverse Visualizer.""" + +from typing import Literal + +from isaaclab.utils import configclass + +from .visualizer_cfg import VisualizerCfg + + +@configclass +class OVVisualizerCfg(VisualizerCfg): + """Configuration for Omniverse Visualizer. + + The Omniverse Visualizer uses the Omniverse SDK to provide high-fidelity + visualization of the simulation. This is currently implemented through the + Isaac Sim app, but will eventually use the standalone Omniverse SDK module. + + Features: + - High-fidelity rendering with RTX + - Full visual shape support (not just collision shapes) + - USD-based scene representation + - Advanced lighting and materials + - Integration with Omniverse ecosystem + + Note: + The Omniverse Visualizer has higher overhead than the Newton Visualizer + and requires Omniverse/Isaac Sim to be installed. + """ + + # Override defaults for Omniverse visualizer + camera_position: tuple[float, float, float] = (10.0, 10.0, 10.0) + """Initial position of the camera. Default is (10.0, 10.0, 10.0).""" + + window_width: int = 1920 + """Width of the visualizer window in pixels. Default is 1920.""" + + window_height: int = 1080 + """Height of the visualizer window in pixels. Default is 1080.""" + + # Omniverse-specific settings + viewport_name: str = "/OmniverseKit_Persp" + """Name of the viewport to use for visualization. Default is "/OmniverseKit_Persp".""" + + show_origin_axis: bool = True + """Whether to show the origin axis. Default is True.""" + + show_grid: bool = True + """Whether to show the grid. Default is True.""" + + grid_scale: float = 1.0 + """Scale of the grid. Default is 1.0.""" + + enable_scene_lights: bool = True + """Whether to enable scene lights. Default is True.""" + + default_light_intensity: float = 3000.0 + """Default intensity for scene lights. Default is 3000.0.""" + + enable_dome_light: bool = True + """Whether to enable dome (environment) lighting. Default is True.""" + + dome_light_intensity: float = 1000.0 + """Intensity of the dome light. Default is 1000.0.""" + + dome_light_texture: str | None = None + """Path to HDR texture for dome light. Default is None (use default). + + If specified, should be a path to an HDR image file for image-based lighting. + """ + + camera_projection: Literal["perspective", "orthographic"] = "perspective" + """Camera projection type. Default is "perspective".""" + + fov: float = 60.0 + """Field of view for the camera in degrees (for perspective projection). Default is 60.0.""" + + near_plane: float = 0.1 + """Near clipping plane distance. Default is 0.1.""" + + far_plane: float = 10000.0 + """Far clipping plane distance. Default is 10000.0.""" + + enable_ui: bool = True + """Whether to enable the Omniverse UI. Default is True. + + When disabled, runs in a more minimal mode which can improve performance. + """ + + ui_window_layout: str | None = None + """Custom UI window layout file. Default is None (use default layout). + + Can be a path to a .json file specifying the UI layout. + """ + + show_selection_outline: bool = True + """Whether to show selection outline on picked objects. Default is True.""" + + show_physics_debug_viz: bool = False + """Whether to show physics debug visualization (contacts, joints). Default is False.""" + + show_bounding_boxes: bool = False + """Whether to show bounding boxes. Default is False.""" + + display_options: int = 3094 + """Display options bitmask. Default is 3094. + + This controls what is visible in the stage. The default value (3094) hides + extra objects that shouldn't appear in visualization. Another common value + is 3286 for the regular editor experience. + """ + + enable_live_sync: bool = False + """Whether to enable live sync with Omniverse. Default is False. + + When enabled, allows other Omniverse clients to connect and view the simulation. + """ + + antialiasing: Literal["Off", "FXAA", "TAA", "DLSS", "DLAA"] = "TAA" + """Anti-aliasing mode. Default is "TAA". + + - Off: No anti-aliasing + - FXAA: Fast approximate anti-aliasing + - TAA: Temporal anti-aliasing + - DLSS: NVIDIA Deep Learning Super Sampling (requires RTX GPU) + - DLAA: NVIDIA Deep Learning Anti-Aliasing (requires RTX GPU) + """ + + enable_post_processing: bool = True + """Whether to enable post-processing effects. Default is True.""" + + enable_motion_blur: bool = False + """Whether to enable motion blur. Default is False.""" + + enable_depth_of_field: bool = False + """Whether to enable depth of field. Default is False.""" + + background_color: tuple[float, float, float] = (0.0, 0.0, 0.0) + """Background color as RGB values in range [0, 1]. Default is (0.0, 0.0, 0.0) (black).""" + + capture_on_play: bool = False + """Whether to start capturing when play is pressed. Default is False. + + Useful for recording the simulation for later playback. + """ + + capture_path: str | None = None + """Path to save captures. Default is None (don't capture). + + When specified, frames will be captured to this path. + """ + + capture_format: Literal["png", "jpg", "exr"] = "png" + """Format for captured images. Default is "png".""" + + diff --git a/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer_cfg.py b/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer_cfg.py new file mode 100644 index 00000000000..487bc6e69eb --- /dev/null +++ b/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer_cfg.py @@ -0,0 +1,159 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Configuration for Rerun Visualizer.""" + +from typing import Literal + +from isaaclab.utils import configclass + +from .visualizer_cfg import VisualizerCfg + + +@configclass +class RerunVisualizerCfg(VisualizerCfg): + """Configuration for Rerun Visualizer. + + The Rerun Visualizer integrates with the rerun visualization library, enabling + real-time or offline visualization with advanced features like time scrubbing + and data inspection through a web-based interface. + + Features: + - Web-based visualization interface + - Time scrubbing and playback controls + - 3D scene navigation + - Data inspection and filtering + - Recording and export capabilities + - Remote viewing support + + Note: + Requires the rerun-sdk package to be installed: pip install rerun-sdk + """ + + # Override defaults for Rerun visualizer + camera_position: tuple[float, float, float] = (10.0, 10.0, 10.0) + """Initial position of the camera. Default is (10.0, 10.0, 10.0).""" + + # Rerun-specific settings + server_mode: bool = True + """Whether to run in server mode. Default is True. + + In server mode, Rerun starts a server that viewers can connect to. + When False, data is logged to a file or sent to an external viewer. + """ + + server_address: str = "127.0.0.1:9876" + """Server address for Rerun. Default is "127.0.0.1:9876". + + Format: "host:port". Only used when server_mode is True. + """ + + launch_viewer: bool = True + """Whether to automatically launch the web viewer. Default is True. + + When True, the Rerun web viewer will be automatically opened in a browser. + """ + + app_id: str = "isaaclab-simulation" + """Application identifier for Rerun. Default is "isaaclab-simulation". + + This is used to identify the application in the Rerun viewer and for + organizing recordings. + """ + + recording_path: str | None = None + """Path to save recordings. Default is None (don't save). + + When specified, the Rerun data will be saved to this path for later replay. + Supported formats: .rrd (Rerun recording format) + """ + + spawn_mode: Literal["connect", "spawn", "save"] = "spawn" + """How to handle the Rerun viewer. Default is "spawn". + + - "connect": Connect to an existing Rerun viewer + - "spawn": Spawn a new Rerun viewer process + - "save": Save to a file without opening a viewer + """ + + max_queue_size: int = 100 + """Maximum number of messages to queue. Default is 100. + + Controls memory usage for buffering visualization data. + """ + + flush_timeout: float = 2.0 + """Timeout for flushing data to Rerun in seconds. Default is 2.0.""" + + log_transforms: bool = True + """Whether to log rigid body transforms. Default is True.""" + + log_meshes: bool = True + """Whether to log mesh data. Default is True. + + When enabled, collision and visual meshes will be logged to Rerun. + """ + + log_cameras: bool = True + """Whether to log camera data. Default is True.""" + + log_point_clouds: bool = False + """Whether to log point cloud data. Default is False.""" + + log_images: bool = False + """Whether to log images from cameras. Default is False. + + Note: Logging images can significantly increase data size and bandwidth. + """ + + log_tensors: bool = False + """Whether to log tensor data (observations, actions, etc.). Default is False. + + When enabled, can log observation buffers, action buffers, and other tensors. + """ + + time_mode: Literal["sim_time", "wall_time", "step_count"] = "sim_time" + """Time mode for logging. Default is "sim_time". + + - "sim_time": Use simulation time as the timeline + - "wall_time": Use wall clock time + - "step_count": Use step count as the timeline + """ + + entity_path_prefix: str = "/world" + """Prefix for entity paths in Rerun. Default is "/world". + + All logged entities will be under this prefix in the Rerun hierarchy. + """ + + log_static_once: bool = True + """Whether to log static scene data only once. Default is True. + + When True, static meshes and other unchanging data are logged only at the + start, reducing data size and bandwidth. + """ + + up_axis: Literal["+x", "-x", "+y", "-y", "+z", "-z"] = "+z" + """The up axis for the 3D space. Default is "+z". + + This should match your simulation's coordinate system. + """ + + mesh_quality: Literal["low", "medium", "high"] = "medium" + """Quality level for mesh data. Default is "medium". + + Higher quality preserves more detail but increases data size. + """ + + enable_compression: bool = True + """Whether to enable data compression. Default is True. + + Compression reduces bandwidth and storage requirements but adds CPU overhead. + """ + + verbose: bool = False + """Whether to enable verbose logging. Default is False.""" + + diff --git a/source/isaaclab/isaaclab/sim/visualizers/visualizer_cfg.py b/source/isaaclab/isaaclab/sim/visualizers/visualizer_cfg.py new file mode 100644 index 00000000000..fce04f0c786 --- /dev/null +++ b/source/isaaclab/isaaclab/sim/visualizers/visualizer_cfg.py @@ -0,0 +1,89 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Base configuration for visualizers.""" + +from typing import Literal + +from isaaclab.utils import configclass + + +@configclass +class VisualizerCfg: + """Base configuration for visualizer backends. + + This is the base class for all visualizer configurations. Visualizers are used + for debug visualization and monitoring during simulation, separate from rendering + for sensors/cameras. + + All visualizer backends should inherit from this class and add their specific + configuration parameters. + """ + + enabled: bool = False + """Whether the visualizer is enabled. Default is False.""" + + update_frequency: int = 1 + """Frequency of updates to the visualizer (in simulation steps). + + Higher values (e.g., 10) mean the visualizer updates less frequently, improving + performance at the cost of less responsive visualization. Lower values (e.g., 1) + provide more responsive visualization but may impact performance. + Default is 1 (update every step). + """ + + env_indices: list[int] | None = None + """List of environment indices to visualize. Default is None. + + If None, all environments will be visualized. If a list is provided, only the + specified environments will be visualized. This is useful for reducing the + visualization overhead when running with many environments. + + Example: [0, 1, 2] will visualize only the first 3 environments. + """ + + enable_markers: bool = True + """Whether to enable visualization markers (debug drawing). Default is True. + + Visualization markers are used for debug drawing of points, lines, frames, etc. + These correspond to the VisualizationMarkers class in isaaclab.markers. + """ + + enable_live_plots: bool = True + """Whether to enable live plotting of data. Default is True. + + Live plots can be used to visualize real-time data such as observations, + rewards, and other metrics during simulation. + """ + + train_mode: bool = True + """Whether the visualizer is in training mode (True) or play/inference mode (False). + + This affects the UI and controls displayed in the visualizer. In training mode, + additional controls may be shown for pausing training, adjusting update frequency, etc. + Default is True. + """ + + camera_position: tuple[float, float, float] = (10.0, 0.0, 3.0) + """Initial position of the camera in the visualizer. Default is (10.0, 0.0, 3.0).""" + + camera_target: tuple[float, float, float] = (0.0, 0.0, 0.0) + """Initial target (look-at point) of the camera. Default is (0.0, 0.0, 0.0).""" + + window_width: int = 1920 + """Width of the visualizer window in pixels. Default is 1920.""" + + window_height: int = 1080 + """Height of the visualizer window in pixels. Default is 1080.""" + + def get_visualizer_type(self) -> str: + """Get the type of visualizer as a string. + + Returns: + String identifier for the visualizer type. + """ + return self.__class__.__name__.replace("VisualizerCfg", "").replace("Cfg", "") + + From d70b0d8998d5c0a718319b392af62e3df88f3995 Mon Sep 17 00:00:00 2001 From: mtrepte Date: Mon, 10 Nov 2025 21:01:22 -0800 Subject: [PATCH 02/24] initial impl --- .../isaaclab/sim/_impl/newton_manager.py | 84 ------- .../isaaclab/isaaclab/sim/simulation_cfg.py | 33 ++- .../isaaclab/sim/simulation_context.py | 130 +++++++++- .../isaaclab/sim/visualizers/__init__.py | 16 +- .../newton_visualizer.py} | 230 ++++++++++++++++-- .../isaaclab/sim/visualizers/ov_visualizer.py | 0 .../sim/visualizers/rerun_visualizer.py | 0 .../isaaclab/sim/visualizers/visualizer.py | 129 ++++++++++ .../isaaclab_tasks/utils/parse_cfg.py | 14 +- 9 files changed, 509 insertions(+), 127 deletions(-) rename source/isaaclab/isaaclab/sim/{_impl/newton_viewer.py => visualizers/newton_visualizer.py} (52%) create mode 100644 source/isaaclab/isaaclab/sim/visualizers/ov_visualizer.py create mode 100644 source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer.py create mode 100644 source/isaaclab/isaaclab/sim/visualizers/visualizer.py diff --git a/source/isaaclab/isaaclab/sim/_impl/newton_manager.py b/source/isaaclab/isaaclab/sim/_impl/newton_manager.py index 248d8161901..fb770d6aff3 100644 --- a/source/isaaclab/isaaclab/sim/_impl/newton_manager.py +++ b/source/isaaclab/isaaclab/sim/_impl/newton_manager.py @@ -16,7 +16,6 @@ from newton.solvers import SolverBase, SolverFeatherstone, SolverMuJoCo, SolverXPBD from isaaclab.sim._impl.newton_manager_cfg import NewtonCfg -from isaaclab.sim._impl.newton_viewer import NewtonViewerGL from isaaclab.utils.timer import Timer @@ -66,7 +65,6 @@ class NewtonManager: _report_contacts: bool = False _graph = None _newton_stage_path = None - _renderer = None _sim_time = 0.0 _usdrt_stage = None _newton_index_attr = "newton:index" @@ -76,10 +74,6 @@ class NewtonManager: _gravity_vector: tuple[float, float, float] = (0.0, 0.0, -9.81) _up_axis: str = "Z" _num_envs: int = None - _visualizer_update_counter: int = 0 - _visualizer_update_frequency: int = 1 # Configurable frequency for all rendering updates - _visualizer_train_mode: bool = True # Whether visualizer is in training mode - _visualizer_disabled: bool = False # Whether visualizer has been disabled by user @classmethod def clear(cls): @@ -95,7 +89,6 @@ def clear(cls): NewtonManager._report_contacts = False NewtonManager._graph = None NewtonManager._newton_stage_path = None - NewtonManager._renderer = None NewtonManager._sim_time = 0.0 NewtonManager._on_init_callbacks = [] NewtonManager._on_start_callbacks = [] @@ -103,9 +96,6 @@ def clear(cls): NewtonManager._cfg = NewtonCfg() NewtonManager._up_axis = "Z" NewtonManager._first_call = True - NewtonManager._visualizer_update_counter = 0 - NewtonManager._visualizer_disabled = False - NewtonManager._visualizer_update_frequency = NewtonManager._cfg.newton_viewer_update_frequency @classmethod def set_builder(cls, builder): @@ -302,80 +292,6 @@ def set_simulation_dt(cls, dt: float) -> None: """ NewtonManager._dt = dt - @classmethod - def _render_call(cls, render_func) -> bool: - if NewtonManager._renderer is not None: - try: - if hasattr(NewtonManager._renderer, "renderer") and hasattr(NewtonManager._renderer.renderer, "window"): - if NewtonManager._renderer.renderer.window.has_exit: - NewtonManager._visualizer_disabled = True - NewtonManager._renderer = None - return False - except Exception as e: - print(f"[ERROR] Error in _render_call: {e}") - - try: - render_func() - return True - except (ctypes.ArgumentError, Exception) as e: - if "wrong type" in str(e) or "ArgumentError" in str(e): - NewtonManager._visualizer_disabled = True - if NewtonManager._renderer is not None: - try: - NewtonManager._renderer.close() - except Exception as e: - print(f"[ERROR] Error in _render_call: {e}") - NewtonManager._renderer = None - return False - else: - raise - - @classmethod - def render(cls) -> None: - if NewtonManager._visualizer_disabled: - return - - if NewtonManager._renderer is None: - NewtonManager._visualizer_train_mode = NewtonManager._cfg.visualizer_train_mode - NewtonManager._renderer = NewtonViewerGL( - width=1280, height=720, train_mode=NewtonManager._visualizer_train_mode - ) - NewtonManager._renderer.set_model(NewtonManager._model) - NewtonManager._renderer.camera.pos = wp.vec3(*NewtonManager._cfg.newton_viewer_camera_pos) - NewtonManager._renderer.up_axis = NewtonManager._up_axis - NewtonManager._renderer.scaling = 1.0 - NewtonManager._renderer._paused = False - else: - while NewtonManager._renderer is not None and NewtonManager._renderer.is_training_paused(): - - def render_frame(): - NewtonManager._renderer.begin_frame(NewtonManager._sim_time) - NewtonManager._renderer.log_state(NewtonManager._state_0) - NewtonManager._renderer.end_frame() - - if not NewtonManager._render_call(render_frame): - return - - NewtonManager._visualizer_update_counter += 1 - if ( - NewtonManager._renderer is not None - and NewtonManager._visualizer_update_counter >= NewtonManager._visualizer_update_frequency - ): - if not NewtonManager._renderer.is_paused(): - - def render_frame(): - NewtonManager._renderer.begin_frame(NewtonManager._sim_time) - NewtonManager._renderer.log_state(NewtonManager._state_0) - NewtonManager._renderer.end_frame() - - if not NewtonManager._render_call(render_frame): - return - else: - if not NewtonManager._render_call(lambda: NewtonManager._renderer._update()): - return - - NewtonManager._visualizer_update_counter = 0 - @classmethod def sync_fabric_transforms(cls) -> None: """Syncs the fabric transforms with the Newton state. diff --git a/source/isaaclab/isaaclab/sim/simulation_cfg.py b/source/isaaclab/isaaclab/sim/simulation_cfg.py index f6f2dfd5957..4e46f75fcff 100644 --- a/source/isaaclab/isaaclab/sim/simulation_cfg.py +++ b/source/isaaclab/isaaclab/sim/simulation_cfg.py @@ -197,28 +197,35 @@ class SimulationCfg: render: RenderCfg = RenderCfg() """Render settings. Default is RenderCfg().""" - enable_newton_rendering: bool = False - """Enable/disable rendering using Newton. Default is False. - - When enabled, the Newton to renderer will be called every time the simulation is rendered. If Isaac Sim's - renderer is also enabled, both will be called. - """ - - visualizer: VisualizerCfg | None = None + visualizers: list[VisualizerCfg] | VisualizerCfg | None = None """Visualizer settings. Default is None (no visualizer). - To enable a visualizer, set this to one of the visualizer configuration classes: + This field supports multiple visualizer backends for debug visualization and monitoring + during simulation. It accepts: + - A single VisualizerCfg: One visualizer will be created + - A list of VisualizerCfg: Multiple visualizers will be created + - None or empty list: No visualizers will be created + + Supported visualizer backends: - NewtonVisualizerCfg: Lightweight OpenGL-based visualizer - OVVisualizerCfg: Omniverse-based high-fidelity visualizer - RerunVisualizerCfg: Web-based Rerun visualizer - Example: + Examples: + # Single visualizer from isaaclab.sim.visualizers import NewtonVisualizerCfg - cfg = SimulationCfg(visualizer=NewtonVisualizerCfg(enabled=True)) + cfg = SimulationCfg(visualizers=NewtonVisualizerCfg(enabled=True)) + + # Multiple visualizers + from isaaclab.sim.visualizers import NewtonVisualizerCfg, RerunVisualizerCfg + cfg = SimulationCfg(visualizers=[ + NewtonVisualizerCfg(enabled=True), + RerunVisualizerCfg(enabled=True) + ]) Note: - This replaces the previous enable_newton_rendering flag and provides a unified - interface for all visualizer backends. + Visualizers are separate from rendering backends (for cameras/sensors). + They are intended for debug visualization and monitoring only. """ create_stage_in_memory: bool = False diff --git a/source/isaaclab/isaaclab/sim/simulation_context.py b/source/isaaclab/isaaclab/sim/simulation_context.py index 33c93873c1c..9664c44da99 100644 --- a/source/isaaclab/isaaclab/sim/simulation_context.py +++ b/source/isaaclab/isaaclab/sim/simulation_context.py @@ -35,6 +35,7 @@ from .simulation_cfg import SimulationCfg from .spawners import DomeLightCfg, GroundPlaneCfg from .utils import bind_physics_material +from .visualizers import Visualizer, NewtonVisualizer, NewtonVisualizerCfg class SimulationContext(_SimulationContext): @@ -252,6 +253,10 @@ def __init__(self, cfg: SimulationCfg | None = None): self._app_control_on_stop_handle = None self._disable_app_control_on_stop_handle = False + # initialize visualizers + self._visualizers: list[Visualizer] = [] + self._visualizer_step_counter = 0 + # flag for skipping prim deletion callback # when stage in memory is attached self._skip_next_prim_deletion_callback_fn = False @@ -538,6 +543,118 @@ def forward(self) -> None: NewtonManager.forward_kinematics() NewtonManager.sync_fabric_transforms() + def initialize_visualizers(self) -> None: + """Initialize all configured visualizers. + + This method creates and initializes visualizers based on the configuration provided + in SimulationCfg.visualizers. It supports: + - A single VisualizerCfg: Creates one visualizer + - A list of VisualizerCfg: Creates multiple visualizers + - None or empty list: No visualizers are created + """ + # Handle different input formats + visualizer_cfgs = [] + if self.cfg.visualizers is not None: + if isinstance(self.cfg.visualizers, list): + visualizer_cfgs = [cfg for cfg in self.cfg.visualizers if cfg.enabled] + elif self.cfg.visualizers.enabled: + visualizer_cfgs = [self.cfg.visualizers] + + # Create and initialize each visualizer + for viz_cfg in visualizer_cfgs: + try: + # Create visualizer instance based on config type + if isinstance(viz_cfg, NewtonVisualizerCfg): + visualizer = NewtonVisualizer(viz_cfg) + else: + # Skip unsupported visualizer types for now + omni.log.warn( + f"Visualizer type '{type(viz_cfg).__name__}' is not yet implemented. Skipping." + ) + continue + + # Initialize with Newton model if available + if NewtonManager._model is not None: + scene = { + "model": NewtonManager._model, + "state": NewtonManager._state_0, + } + visualizer.initialize(scene) + self._visualizers.append(visualizer) + omni.log.info(f"Initialized visualizer: {type(visualizer).__name__}") + else: + omni.log.warn( + "Newton model not available yet. Visualizer will be initialized later." + ) + + except Exception as e: + omni.log.error(f"Failed to initialize visualizer '{type(viz_cfg).__name__}': {e}") + + def step_visualizers(self, dt: float) -> None: + """Update all active visualizers. + + This method steps all initialized visualizers and updates their state. + It also handles visualizer pause states and removes closed visualizers. + + Args: + dt: Time step in seconds. + """ + if not self._visualizers: + return + + self._visualizer_step_counter += 1 + + # Update visualizers and check if any should be removed + visualizers_to_remove = [] + + for visualizer in self._visualizers: + try: + # Check if visualizer is still running + if not visualizer.is_running(): + visualizers_to_remove.append(visualizer) + continue + + # Handle training pause - block until resumed + while visualizer.is_training_paused() and visualizer.is_running(): + if isinstance(visualizer, NewtonVisualizer): + # Update state before rendering during pause + visualizer.update_state(NewtonManager._state_0) + visualizer.step(0.0) # Step with 0 dt during pause + + # Skip rendering if visualizer has rendering paused + if visualizer.is_rendering_paused(): + continue + + # Normal step: update state and visualizer + if isinstance(visualizer, NewtonVisualizer): + visualizer.update_state(NewtonManager._state_0) + + visualizer.step(dt) + + except Exception as e: + omni.log.error(f"Error stepping visualizer '{type(visualizer).__name__}': {e}") + visualizers_to_remove.append(visualizer) + + # Remove closed visualizers + for visualizer in visualizers_to_remove: + try: + visualizer.close() + self._visualizers.remove(visualizer) + omni.log.info(f"Removed visualizer: {type(visualizer).__name__}") + except Exception as e: + omni.log.error(f"Error closing visualizer: {e}") + + def close_visualizers(self) -> None: + """Close all active visualizers and clean up resources.""" + for visualizer in self._visualizers: + try: + visualizer.close() + except Exception as e: + omni.log.error(f"Error closing visualizer '{type(visualizer).__name__}': {e}") + + self._visualizers.clear() + omni.log.info("All visualizers closed") + def get_initial_stage(self) -> Usd.Stage: """Returns stage handle used during scene creation. @@ -577,6 +694,11 @@ def reset(self, soft: bool = False): if not soft: for _ in range(2): self.render() + + # Initialize visualizers after simulation is set up (only on first reset) + if not soft and not self._visualizers: + self.initialize_visualizers() + self._disable_app_control_on_stop_handle = False def step(self, render: bool = True): @@ -628,9 +750,8 @@ def step(self, render: bool = True): if self.is_playing(): NewtonManager.step() - # Use the NewtonManager to render the scene if enabled - if self.cfg.enable_newton_rendering: - NewtonManager.render() + # Update visualizers + self.step_visualizers(self.cfg.dt) # app.update() may be changing the cuda device in step, so we force it back to our desired device here if "cuda" in self.device: @@ -728,6 +849,9 @@ def clear_instance(cls): if cls._instance._app_control_on_stop_handle is not None: cls._instance._app_control_on_stop_handle.unsubscribe() cls._instance._app_control_on_stop_handle = None + # close all visualizers + if hasattr(cls._instance, '_visualizers'): + cls._instance.close_visualizers() # call parent to clear the instance super().clear_instance() NewtonManager.clear() diff --git a/source/isaaclab/isaaclab/sim/visualizers/__init__.py b/source/isaaclab/isaaclab/sim/visualizers/__init__.py index 64a9dcf7f51..0814b88a412 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/__init__.py +++ b/source/isaaclab/isaaclab/sim/visualizers/__init__.py @@ -3,25 +3,29 @@ # # SPDX-License-Identifier: BSD-3-Clause -"""Sub-package for visualizer configurations. +"""Sub-package for visualizer configurations and implementations. -This sub-package contains configuration classes for different visualizer backends -that can be used with Isaac Lab. The visualizers are used for debug visualization -and monitoring of the simulation, separate from rendering for sensors. +This sub-package contains configuration classes and implementations for different +visualizer backends that can be used with Isaac Lab. The visualizers are used for +debug visualization and monitoring of the simulation, separate from rendering for sensors. Supported visualizers: - Newton OpenGL Visualizer: Lightweight OpenGL-based visualizer -- Omniverse Visualizer: High-fidelity Omniverse-based visualizer -- Rerun Visualizer: Web-based visualizer using the rerun library +- Omniverse Visualizer: High-fidelity Omniverse-based visualizer (coming soon) +- Rerun Visualizer: Web-based visualizer using the rerun library (coming soon) """ +from .visualizer import Visualizer from .visualizer_cfg import VisualizerCfg +from .newton_visualizer import NewtonVisualizer from .newton_visualizer_cfg import NewtonVisualizerCfg from .ov_visualizer_cfg import OVVisualizerCfg from .rerun_visualizer_cfg import RerunVisualizerCfg __all__ = [ + "Visualizer", "VisualizerCfg", + "NewtonVisualizer", "NewtonVisualizerCfg", "OVVisualizerCfg", "RerunVisualizerCfg", diff --git a/source/isaaclab/isaaclab/sim/_impl/newton_viewer.py b/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py similarity index 52% rename from source/isaaclab/isaaclab/sim/_impl/newton_viewer.py rename to source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py index 00f13dc9202..ac9ed2c217c 100644 --- a/source/isaaclab/isaaclab/sim/_impl/newton_viewer.py +++ b/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py @@ -3,30 +3,34 @@ # # SPDX-License-Identifier: BSD-3-Clause -""" -Training-aware viewer that adds a separate pause for simulation/training while keeping rendering at full rate. - -This class subclasses Newton's ViewerGL and introduces a second pause mode: -- Rendering pause: identical to the base viewer's pause (space key / Pause checkbox) -- Training pause: stops simulation/training steps but keeps rendering running - -The training pause can be toggled from the UI via a button and optionally via the 'T' key. -""" +"""Newton OpenGL Visualizer implementation.""" from __future__ import annotations -import newton as nt import warp as wp from newton.viewer import ViewerGL +from .newton_visualizer_cfg import NewtonVisualizerCfg +from .visualizer import Visualizer + class NewtonViewerGL(ViewerGL): + """Training-aware viewer that adds a separate pause for simulation/training. + + This class subclasses Newton's ViewerGL and introduces a second pause mode: + - Rendering pause: identical to the base viewer's pause (space key / Pause checkbox) + - Training pause: stops simulation/training steps but keeps rendering running + + The training pause can be toggled from the UI via a button and optionally via the 'T' key. + """ + def __init__(self, *args, train_mode: bool = True, **kwargs): super().__init__(*args, **kwargs) self._paused_training: bool = False self._paused_rendering: bool = False self._fallback_draw_controls: bool = False - self._is_train_mode: bool = train_mode # Convert train_mode to play_mode + self._is_train_mode: bool = train_mode + self._visualizer_update_frequency: int = 1 try: self.register_ui_callback(self._render_training_controls, position="side") @@ -34,11 +38,33 @@ def __init__(self, *args, train_mode: bool = True, **kwargs): self._fallback_draw_controls = True def is_training_paused(self) -> bool: + """Check if training is paused.""" return self._paused_training def is_paused(self) -> bool: + """Check if rendering is paused.""" return self._paused_rendering + def is_rendering_paused(self) -> bool: + """Check if rendering is paused (alias for is_paused for consistency).""" + return self._paused_rendering + + def set_visualizer_update_frequency(self, frequency: int) -> None: + """Set the visualizer update frequency. + + Args: + frequency: Number of simulation steps between visualizer updates. + """ + self._visualizer_update_frequency = max(1, frequency) + + def get_visualizer_update_frequency(self) -> int: + """Get the current visualizer update frequency. + + Returns: + Number of simulation steps between visualizer updates. + """ + return self._visualizer_update_frequency + # UI callback rendered inside the "Example Options" panel of the left sidebar def _render_training_controls(self, imgui): imgui.separator() @@ -60,17 +86,14 @@ def _render_training_controls(self, imgui): if imgui.button(rendering_label): self._paused_rendering = not self._paused_rendering - # Import NewtonManager locally to avoid circular imports - from .newton_manager import NewtonManager # noqa: PLC0415 - imgui.text("Visualizer Update Frequency") - current_frequency = NewtonManager._visualizer_update_frequency + current_frequency = self._visualizer_update_frequency changed, new_frequency = imgui.slider_int( "##VisualizerUpdateFreq", current_frequency, 1, 20, f"Every {current_frequency} frames" ) if changed: - NewtonManager._visualizer_update_frequency = new_frequency + self._visualizer_update_frequency = new_frequency if imgui.is_item_hovered(): imgui.set_tooltip( @@ -119,6 +142,8 @@ def _render_ui(self): def _render_left_panel(self): """Override the left panel to remove the base pause checkbox.""" + import newton as nt + imgui = self.ui.imgui # Use theme colors directly @@ -228,3 +253,176 @@ def _render_left_panel(self): imgui.end() return + + +class NewtonVisualizer(Visualizer): + """Newton OpenGL Visualizer for Isaac Lab. + + This visualizer uses Newton's OpenGL-based viewer to provide lightweight, + fast visualization of simulations. It includes IsaacLab-specific features + like training controls, rendering pause, and update frequency adjustment. + + Args: + cfg: Configuration for the Newton visualizer. + """ + + def __init__(self, cfg: NewtonVisualizerCfg): + super().__init__(cfg) + self.cfg: NewtonVisualizerCfg = cfg + self._viewer: NewtonViewerGL | None = None + self._sim_time: float = 0.0 + self._step_counter: int = 0 + self._model = None + self._state = None + + def initialize(self, scene) -> None: + """Initialize the Newton visualizer with the simulation scene. + + Args: + scene: Dictionary containing 'model' and 'state' for Newton simulation, + or the Newton Model object directly. + """ + if self._is_initialized: + return + + # Extract model and state from scene + if isinstance(scene, dict): + self._model = scene.get("model") + self._state = scene.get("state") + else: + # Assume scene is the Newton Model + self._model = scene + self._state = None + + if self._model is None: + raise ValueError("Newton visualizer requires a Newton Model to be provided in the scene") + + # Create the viewer + self._viewer = NewtonViewerGL( + width=self.cfg.window_width, + height=self.cfg.window_height, + train_mode=self.cfg.train_mode, + ) + + # Set the model + self._viewer.set_model(self._model) + + # Configure camera + self._viewer.camera.pos = wp.vec3(*self.cfg.camera_position) + self._viewer.up_axis = ["X", "Y", "Z"].index(self.cfg.up_axis) + self._viewer.scaling = 1.0 + self._viewer._paused = False + + # Configure visualization options + self._viewer.show_joints = self.cfg.show_joints + self._viewer.show_contacts = self.cfg.show_contacts + self._viewer.show_springs = self.cfg.show_springs + self._viewer.show_com = self.cfg.show_com + + # Configure rendering options + self._viewer.renderer.draw_shadows = self.cfg.enable_shadows + self._viewer.renderer.draw_sky = self.cfg.enable_sky + self._viewer.renderer.draw_wireframe = self.cfg.enable_wireframe + + # Configure colors + self._viewer.renderer.sky_upper = self.cfg.background_color + self._viewer.renderer.sky_lower = self.cfg.ground_color + self._viewer.renderer._light_color = self.cfg.light_color + + # Set update frequency + self._viewer.set_visualizer_update_frequency(self.cfg.update_frequency) + + self._is_initialized = True + + def step(self, dt: float) -> None: + """Update the visualizer for one simulation step. + + Args: + dt: Time step in seconds since last visualization update. + + Note: + Pause handling (training and rendering) is managed by SimulationContext. + This method only performs the actual rendering when called. + The visualizer MUST be called every frame to maintain proper ImGui state, + even if we skip rendering some frames based on update_frequency. + """ + if not self._is_initialized or self._is_closed or self._viewer is None: + return + + # Update simulation time + self._sim_time += dt + + # Render the current frame + # Note: We always call begin_frame/end_frame to maintain ImGui state + # The update frequency is handled internally by the viewer + try: + self._viewer.begin_frame(self._sim_time) + try: + if self._state is not None: + self._viewer.log_state(self._state) + finally: + # Always call end_frame if begin_frame succeeded + self._viewer.end_frame() + except Exception as e: + # Handle any rendering errors gracefully + # Frame lifecycle is now properly handled by try-finally + pass # Silently ignore to avoid log spam - the viewer will recover + + def close(self) -> None: + """Close the visualizer and clean up resources.""" + if self._is_closed: + return + + if self._viewer is not None: + try: + # Newton viewer doesn't have an explicit close method, + # but we can clean up our reference + self._viewer = None + except Exception as e: + print(f"[Warning] Error closing Newton visualizer: {e}") + + self._is_closed = True + + def is_running(self) -> bool: + """Check if the visualizer is still running. + + Returns: + True if the visualizer window is open and running. + """ + if not self._is_initialized or self._is_closed or self._viewer is None: + return False + + return self._viewer.is_running() + + def is_training_paused(self) -> bool: + """Check if training is paused by the visualizer. + + Returns: + True if the user has paused training via the visualizer controls. + """ + if not self._is_initialized or self._viewer is None: + return False + + return self._viewer.is_training_paused() + + def is_rendering_paused(self) -> bool: + """Check if rendering is paused by the visualizer. + + Returns: + True if rendering is paused via the visualizer controls. + """ + if not self._is_initialized or self._viewer is None: + return False + + return self._viewer.is_rendering_paused() + + def update_state(self, state) -> None: + """Update the simulation state for visualization. + + This method should be called before step() to provide the latest simulation state. + + Args: + state: The Newton State object to visualize. + """ + self._state = state + diff --git a/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer.py b/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer.py new file mode 100644 index 00000000000..e69de29bb2d diff --git a/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer.py b/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer.py new file mode 100644 index 00000000000..e69de29bb2d diff --git a/source/isaaclab/isaaclab/sim/visualizers/visualizer.py b/source/isaaclab/isaaclab/sim/visualizers/visualizer.py new file mode 100644 index 00000000000..e118be751f1 --- /dev/null +++ b/source/isaaclab/isaaclab/sim/visualizers/visualizer.py @@ -0,0 +1,129 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Base class for visualizers.""" + +from __future__ import annotations + +from abc import ABC, abstractmethod +from typing import TYPE_CHECKING + +if TYPE_CHECKING: + from .visualizer_cfg import VisualizerCfg + + +class Visualizer(ABC): + """Base class for all visualizer backends. + + Visualizers are used for debug visualization and monitoring during simulation, + separate from rendering for sensors/cameras. Each visualizer backend (Newton OpenGL, + Omniverse, Rerun) should inherit from this class and implement the required methods. + + The visualizer lifecycle follows this pattern: + 1. __init__: Create the visualizer with configuration + 2. initialize: Set up the visualizer with the simulation model/scene + 3. step: Update the visualizer each simulation step + 4. close: Clean up resources when done + + Args: + cfg: Configuration for the visualizer backend. + """ + + def __init__(self, cfg: VisualizerCfg): + """Initialize the visualizer with configuration. + + Args: + cfg: Configuration for the visualizer backend. + """ + self.cfg = cfg + self._is_initialized = False + self._is_closed = False + + @abstractmethod + def initialize(self, scene) -> None: + """Initialize the visualizer with the simulation scene. + + This method is called once after the simulation scene is created and before + the simulation starts. It should set up any necessary resources for visualization. + + Args: + scene: The simulation scene to visualize. This could be a Newton Model, + a USD stage, or other scene representation depending on the backend. + """ + pass + + @abstractmethod + def step(self, dt: float) -> None: + """Update the visualizer for one simulation step. + + This method is called each simulation step to update the visualization. + The frequency of calls is controlled by the update_frequency parameter in the config. + + Args: + dt: Time step in seconds since last visualization update. + """ + pass + + @abstractmethod + def close(self) -> None: + """Close the visualizer and clean up resources. + + This method is called when the simulation is ending or the visualizer + is no longer needed. It should release any resources held by the visualizer. + """ + pass + + @abstractmethod + def is_running(self) -> bool: + """Check if the visualizer is still running. + + Returns: + True if the visualizer is running and should continue receiving updates, + False if it has been closed (e.g., user closed the window). + """ + pass + + def is_training_paused(self) -> bool: + """Check if training/simulation is paused by the visualizer. + + Some visualizers (like Newton OpenGL) provide controls to pause the simulation + while keeping the visualizer running. This is useful for debugging. + + Returns: + True if the user has paused training/simulation, False otherwise. + Default implementation returns False (no pause support). + """ + return False + + def is_rendering_paused(self) -> bool: + """Check if rendering is paused by the visualizer. + + Some visualizers allow pausing rendering while keeping simulation running, + which can improve performance during training. + + Returns: + True if rendering is paused, False otherwise. + Default implementation returns False (no pause support). + """ + return False + + @property + def is_initialized(self) -> bool: + """Check if the visualizer has been initialized. + + Returns: + True if initialize() has been called successfully. + """ + return self._is_initialized + + @property + def is_closed(self) -> bool: + """Check if the visualizer has been closed. + + Returns: + True if close() has been called. + """ + return self._is_closed + diff --git a/source/isaaclab_tasks/isaaclab_tasks/utils/parse_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/utils/parse_cfg.py index 3842bda1471..755c3ad0acf 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/utils/parse_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/utils/parse_cfg.py @@ -119,7 +119,6 @@ def parse_env_cfg( device: str = "cuda:0", num_envs: int | None = None, use_fabric: bool | None = None, - newton_visualizer: bool | None = None, ) -> ManagerBasedRLEnvCfg | DirectRLEnvCfg: """Parse configuration for an environment and override based on inputs. @@ -130,7 +129,6 @@ def parse_env_cfg( use_fabric: Whether to enable/disable fabric interface. If false, all read/write operations go through USD. This slows down the simulation but allows seeing the changes in the USD through the USD stage. Defaults to None, in which case it is left unchanged. - newton_visualizer: Whether to enable/disable Newton rendering. Defaults to None, in which case it is left unchanged. Returns: The parsed configuration object. @@ -138,6 +136,15 @@ def parse_env_cfg( Raises: RuntimeError: If the configuration for the task is not a class. We assume users always use a class for the environment configuration. + + Note: + To enable visualizers, set them directly in the environment configuration using + SimulationCfg.visualizers. For example: + + .. code-block:: python + + from isaaclab.sim.visualizers import NewtonVisualizerCfg + cfg.sim.visualizers = NewtonVisualizerCfg(enabled=True) """ # load the default configuration cfg = load_cfg_from_registry(task_name.split(":")[-1], "env_cfg_entry_point") @@ -155,9 +162,6 @@ def parse_env_cfg( # number of environments if num_envs is not None: cfg.scene.num_envs = num_envs - # newton rendering - if newton_visualizer is not None: - cfg.sim.enable_newton_rendering = newton_visualizer return cfg From d5fcc055ae3de5d486265133b12bd03402eb79b5 Mon Sep 17 00:00:00 2001 From: mtrepte Date: Tue, 11 Nov 2025 22:54:44 -0800 Subject: [PATCH 03/24] add scene data provider abstraction layer --- scripts/environments/random_agent.py | 23 ++++- scripts/environments/zero_agent.py | 23 ++++- .../reinforcement_learning/rl_games/play.py | 23 ++++- .../reinforcement_learning/rl_games/train.py | 23 ++++- scripts/reinforcement_learning/rsl_rl/play.py | 37 ++++++-- .../reinforcement_learning/rsl_rl/train.py | 23 ++++- scripts/reinforcement_learning/sb3/play.py | 23 ++++- scripts/reinforcement_learning/sb3/train.py | 23 ++++- scripts/reinforcement_learning/skrl/play.py | 23 ++++- scripts/reinforcement_learning/skrl/train.py | 23 ++++- scripts/sim2sim_transfer/rsl_rl_transfer.py | 23 ++++- source/isaaclab/isaaclab/sim/__init__.py | 1 + .../isaaclab/sim/_impl/newton_manager_cfg.py | 4 - .../sim/scene_data_providers/__init__.py | 23 +++++ .../newton_scene_data_provider.py | 85 +++++++++++++++++++ .../scene_data_provider.py | 84 ++++++++++++++++++ .../isaaclab/sim/simulation_context.py | 62 ++++++++------ .../isaaclab/sim/visualizers/__init__.py | 65 +++++++++++++- .../sim/visualizers/newton_visualizer.py | 45 +++++----- .../sim/visualizers/newton_visualizer_cfg.py | 4 + .../isaaclab/sim/visualizers/ov_visualizer.py | 18 ++++ .../sim/visualizers/rerun_visualizer.py | 18 ++++ .../isaaclab/sim/visualizers/visualizer.py | 21 +++-- .../sim/visualizers/visualizer_cfg.py | 40 ++++++++- .../isaaclab_tasks/utils/parse_cfg.py | 9 -- 25 files changed, 651 insertions(+), 95 deletions(-) create mode 100644 source/isaaclab/isaaclab/sim/scene_data_providers/__init__.py create mode 100644 source/isaaclab/isaaclab/sim/scene_data_providers/newton_scene_data_provider.py create mode 100644 source/isaaclab/isaaclab/sim/scene_data_providers/scene_data_provider.py diff --git a/scripts/environments/random_agent.py b/scripts/environments/random_agent.py index 46b6cdc1468..653b2be5ccf 100644 --- a/scripts/environments/random_agent.py +++ b/scripts/environments/random_agent.py @@ -18,7 +18,12 @@ ) parser.add_argument("--num_envs", type=int, default=None, help="Number of environments to simulate.") parser.add_argument("--task", type=str, default=None, help="Name of the task.") -parser.add_argument("--newton_visualizer", action="store_true", default=False, help="Enable Newton rendering.") +parser.add_argument( + "--visualize", + action="store_true", + default=False, + help="Launch visualizer(s). Uses visualizers defined in environment config, or defaults to Newton OpenGL if none configured.", +) # append AppLauncher cli args AppLauncher.add_app_launcher_args(parser) # parse the arguments @@ -52,8 +57,22 @@ def main(): device=args_cli.device, num_envs=args_cli.num_envs, use_fabric=not args_cli.disable_fabric, - newton_visualizer=args_cli.newton_visualizer, ) + + # handle visualizer launch + if args_cli.visualize: + from isaaclab.sim.visualizers import NewtonVisualizerCfg + + if env_cfg.sim.visualizers is None: + # No visualizers in config - use default Newton visualizer + env_cfg.sim.visualizers = NewtonVisualizerCfg(enabled=True) + else: + # Enable configured visualizer(s) + if isinstance(env_cfg.sim.visualizers, list): + for viz_cfg in env_cfg.sim.visualizers: + viz_cfg.enabled = True + else: + env_cfg.sim.visualizers.enabled = True # create environment env = gym.make(args_cli.task, cfg=env_cfg) diff --git a/scripts/environments/zero_agent.py b/scripts/environments/zero_agent.py index ab0301b8e7a..d2a3b64541e 100644 --- a/scripts/environments/zero_agent.py +++ b/scripts/environments/zero_agent.py @@ -18,7 +18,12 @@ ) parser.add_argument("--num_envs", type=int, default=None, help="Number of environments to simulate.") parser.add_argument("--task", type=str, default=None, help="Name of the task.") -parser.add_argument("--newton_visualizer", action="store_true", default=False, help="Enable Newton rendering.") +parser.add_argument( + "--visualize", + action="store_true", + default=False, + help="Launch visualizer(s). Uses visualizers defined in environment config, or defaults to Newton OpenGL if none configured.", +) # append AppLauncher cli args AppLauncher.add_app_launcher_args(parser) # parse the arguments @@ -52,8 +57,22 @@ def main(): device=args_cli.device, num_envs=args_cli.num_envs, use_fabric=not args_cli.disable_fabric, - newton_visualizer=args_cli.newton_visualizer, ) + + # handle visualizer launch + if args_cli.visualize: + from isaaclab.sim.visualizers import NewtonVisualizerCfg + + if env_cfg.sim.visualizers is None: + # No visualizers in config - use default Newton visualizer + env_cfg.sim.visualizers = NewtonVisualizerCfg(enabled=True) + else: + # Enable configured visualizer(s) + if isinstance(env_cfg.sim.visualizers, list): + for viz_cfg in env_cfg.sim.visualizers: + viz_cfg.enabled = True + else: + env_cfg.sim.visualizers.enabled = True # create environment env = gym.make(args_cli.task, cfg=env_cfg) diff --git a/scripts/reinforcement_learning/rl_games/play.py b/scripts/reinforcement_learning/rl_games/play.py index ca807368406..8cb49c7098c 100644 --- a/scripts/reinforcement_learning/rl_games/play.py +++ b/scripts/reinforcement_learning/rl_games/play.py @@ -32,7 +32,12 @@ help="When no checkpoint provided, use the last saved model. Otherwise use the best saved model.", ) parser.add_argument("--real-time", action="store_true", default=False, help="Run in real-time, if possible.") -parser.add_argument("--newton_visualizer", action="store_true", default=False, help="Enable Newton rendering.") +parser.add_argument( + "--visualize", + action="store_true", + default=False, + help="Launch visualizer(s). Uses visualizers defined in environment config, or defaults to Newton OpenGL if none configured.", +) # append AppLauncher cli args AppLauncher.add_app_launcher_args(parser) # parse the arguments @@ -84,8 +89,22 @@ def main(): device=args_cli.device, num_envs=args_cli.num_envs, use_fabric=not args_cli.disable_fabric, - newton_visualizer=args_cli.newton_visualizer, ) + + # handle visualizer launch + if args_cli.visualize: + from isaaclab.sim.visualizers import NewtonVisualizerCfg + + if env_cfg.sim.visualizers is None: + # No visualizers in config - use default Newton visualizer + env_cfg.sim.visualizers = NewtonVisualizerCfg(enabled=True) + else: + # Enable configured visualizer(s) + if isinstance(env_cfg.sim.visualizers, list): + for viz_cfg in env_cfg.sim.visualizers: + viz_cfg.enabled = True + else: + env_cfg.sim.visualizers.enabled = True agent_cfg = load_cfg_from_registry(args_cli.task, "rl_games_cfg_entry_point") # specify directory for logging experiments diff --git a/scripts/reinforcement_learning/rl_games/train.py b/scripts/reinforcement_learning/rl_games/train.py index 9e0cfc67739..b12647306da 100644 --- a/scripts/reinforcement_learning/rl_games/train.py +++ b/scripts/reinforcement_learning/rl_games/train.py @@ -38,7 +38,12 @@ const=True, help="if toggled, this experiment will be tracked with Weights and Biases", ) -parser.add_argument("--newton_visualizer", action="store_true", default=False, help="Enable Newton rendering.") +parser.add_argument( + "--visualize", + action="store_true", + default=False, + help="Launch visualizer(s). Uses visualizers defined in environment config, or defaults to Newton OpenGL if none configured.", +) # append AppLauncher cli args AppLauncher.add_app_launcher_args(parser) # parse the arguments @@ -90,7 +95,21 @@ def main(env_cfg: ManagerBasedRLEnvCfg | DirectRLEnvCfg, agent_cfg: dict): # override configurations with non-hydra CLI arguments env_cfg.scene.num_envs = args_cli.num_envs if args_cli.num_envs is not None else env_cfg.scene.num_envs env_cfg.sim.device = args_cli.device if args_cli.device is not None else env_cfg.sim.device - env_cfg.sim.enable_newton_rendering = args_cli.newton_visualizer + + # handle visualizer launch + if args_cli.visualize: + from isaaclab.sim.visualizers import NewtonVisualizerCfg + + if env_cfg.sim.visualizers is None: + # No visualizers in config - use default Newton visualizer + env_cfg.sim.visualizers = NewtonVisualizerCfg(enabled=True) + else: + # Enable configured visualizer(s) + if isinstance(env_cfg.sim.visualizers, list): + for viz_cfg in env_cfg.sim.visualizers: + viz_cfg.enabled = True + else: + env_cfg.sim.visualizers.enabled = True # randomly sample a seed if seed = -1 if args_cli.seed == -1: diff --git a/scripts/reinforcement_learning/rsl_rl/play.py b/scripts/reinforcement_learning/rsl_rl/play.py index 9de5852b233..f703524aec3 100644 --- a/scripts/reinforcement_learning/rsl_rl/play.py +++ b/scripts/reinforcement_learning/rsl_rl/play.py @@ -34,7 +34,12 @@ help="Use the pre-trained checkpoint from Nucleus.", ) parser.add_argument("--real-time", action="store_true", default=False, help="Run in real-time, if possible.") -parser.add_argument("--newton_visualizer", action="store_true", default=False, help="Enable Newton rendering.") +parser.add_argument( + "--visualize", + action="store_true", + default=False, + help="Launch visualizer(s). Uses visualizers defined in environment config, or defaults to Newton OpenGL if none configured.", +) # append RSL-RL cli arguments cli_args.add_rsl_rl_args(parser) # append AppLauncher cli args @@ -96,7 +101,21 @@ def main(env_cfg: ManagerBasedRLEnvCfg | DirectRLEnvCfg, agent_cfg: RslRlBaseRun # note: certain randomizations occur in the environment initialization so we set the seed here env_cfg.seed = agent_cfg.seed env_cfg.sim.device = args_cli.device if args_cli.device is not None else env_cfg.sim.device - env_cfg.sim.enable_newton_rendering = args_cli.newton_visualizer + + # handle visualizer launch + if args_cli.visualize: + from isaaclab.sim.visualizers import NewtonVisualizerCfg + + if env_cfg.sim.visualizers is None: + # No visualizers in config - use default Newton visualizer + env_cfg.sim.visualizers = NewtonVisualizerCfg(enabled=True) + else: + # Enable configured visualizer(s) + if isinstance(env_cfg.sim.visualizers, list): + for viz_cfg in env_cfg.sim.visualizers: + viz_cfg.enabled = True + else: + env_cfg.sim.visualizers.enabled = True # specify directory for logging experiments log_root_path = os.path.join("logs", "rsl_rl", agent_cfg.experiment_name) @@ -117,11 +136,15 @@ def main(env_cfg: ManagerBasedRLEnvCfg | DirectRLEnvCfg, agent_cfg: RslRlBaseRun # set the log directory for the environment (works for all environment types) env_cfg.log_dir = log_dir - # Set play mode for Newton viewer if using Newton visualizer - if args_cli.newton_visualizer: - # Set visualizer to play mode in Newton config - if hasattr(env_cfg.sim, "newton_cfg"): - env_cfg.sim.newton_cfg.visualizer_train_mode = False + # Set play mode for visualizers + if env_cfg.sim.visualizers is not None: + from isaaclab.sim.visualizers import NewtonVisualizerCfg + + if isinstance(env_cfg.sim.visualizers, list): + for viz_cfg in env_cfg.sim.visualizers: + viz_cfg.train_mode = False + elif isinstance(env_cfg.sim.visualizers, NewtonVisualizerCfg): + env_cfg.sim.visualizers.train_mode = False else: # Create newton_cfg if it doesn't exist from isaaclab.sim._impl.newton_manager_cfg import NewtonCfg diff --git a/scripts/reinforcement_learning/rsl_rl/train.py b/scripts/reinforcement_learning/rsl_rl/train.py index 56e712cfe21..63e0dc1293c 100644 --- a/scripts/reinforcement_learning/rsl_rl/train.py +++ b/scripts/reinforcement_learning/rsl_rl/train.py @@ -32,7 +32,12 @@ "--distributed", action="store_true", default=False, help="Run training with multiple GPUs or nodes." ) parser.add_argument("--export_io_descriptors", action="store_true", default=False, help="Export IO descriptors.") -parser.add_argument("--newton_visualizer", action="store_true", default=False, help="Enable Newton rendering.") +parser.add_argument( + "--visualize", + action="store_true", + default=False, + help="Launch visualizer(s). Uses visualizers defined in environment config, or defaults to Newton OpenGL if none configured.", +) # append RSL-RL cli arguments cli_args.add_rsl_rl_args(parser) # append AppLauncher cli args @@ -119,7 +124,21 @@ def main(env_cfg: ManagerBasedRLEnvCfg | DirectRLEnvCfg, agent_cfg: RslRlBaseRun # note: certain randomizations occur in the environment initialization so we set the seed here env_cfg.seed = agent_cfg.seed env_cfg.sim.device = args_cli.device if args_cli.device is not None else env_cfg.sim.device - env_cfg.sim.enable_newton_rendering = args_cli.newton_visualizer + + # handle visualizer launch + if args_cli.visualize: + from isaaclab.sim.visualizers import NewtonVisualizerCfg + + if env_cfg.sim.visualizers is None: + # No visualizers in config - use default Newton visualizer + env_cfg.sim.visualizers = NewtonVisualizerCfg(enabled=True) + else: + # Enable configured visualizer(s) + if isinstance(env_cfg.sim.visualizers, list): + for viz_cfg in env_cfg.sim.visualizers: + viz_cfg.enabled = True + else: + env_cfg.sim.visualizers.enabled = True # multi-gpu training configuration if args_cli.distributed: diff --git a/scripts/reinforcement_learning/sb3/play.py b/scripts/reinforcement_learning/sb3/play.py index 613ec46d7d8..09df5beba36 100644 --- a/scripts/reinforcement_learning/sb3/play.py +++ b/scripts/reinforcement_learning/sb3/play.py @@ -39,7 +39,12 @@ default=False, help="Use a slower SB3 wrapper but keep all the extra training info.", ) -parser.add_argument("--newton_visualizer", action="store_true", default=False, help="Enable Newton rendering.") +parser.add_argument( + "--visualize", + action="store_true", + default=False, + help="Launch visualizer(s). Uses visualizers defined in environment config, or defaults to Newton OpenGL if none configured.", +) # append AppLauncher cli args AppLauncher.add_app_launcher_args(parser) # parse the arguments @@ -87,8 +92,22 @@ def main(): device=args_cli.device, num_envs=args_cli.num_envs, use_fabric=not args_cli.disable_fabric, - newton_visualizer=args_cli.newton_visualizer, ) + + # handle visualizer launch + if args_cli.visualize: + from isaaclab.sim.visualizers import NewtonVisualizerCfg + + if env_cfg.sim.visualizers is None: + # No visualizers in config - use default Newton visualizer + env_cfg.sim.visualizers = NewtonVisualizerCfg(enabled=True) + else: + # Enable configured visualizer(s) + if isinstance(env_cfg.sim.visualizers, list): + for viz_cfg in env_cfg.sim.visualizers: + viz_cfg.enabled = True + else: + env_cfg.sim.visualizers.enabled = True task_name = args_cli.task.split(":")[-1] train_task_name = task_name.replace("-Play", "") diff --git a/scripts/reinforcement_learning/sb3/train.py b/scripts/reinforcement_learning/sb3/train.py index fa34f951ffe..a29a29e66bf 100644 --- a/scripts/reinforcement_learning/sb3/train.py +++ b/scripts/reinforcement_learning/sb3/train.py @@ -32,7 +32,12 @@ default=False, help="Use a slower SB3 wrapper but keep all the extra training info.", ) -parser.add_argument("--newton_visualizer", action="store_true", default=False, help="Enable Newton rendering.") +parser.add_argument( + "--visualize", + action="store_true", + default=False, + help="Launch visualizer(s). Uses visualizers defined in environment config, or defaults to Newton OpenGL if none configured.", +) # append AppLauncher cli args AppLauncher.add_app_launcher_args(parser) # parse the arguments @@ -113,7 +118,21 @@ def main(env_cfg: ManagerBasedRLEnvCfg | DirectRLEnvCfg, agent_cfg: dict): # note: certain randomizations occur in the environment initialization so we set the seed here env_cfg.seed = agent_cfg["seed"] env_cfg.sim.device = args_cli.device if args_cli.device is not None else env_cfg.sim.device - env_cfg.sim.enable_newton_rendering = args_cli.newton_visualizer + + # handle visualizer launch + if args_cli.visualize: + from isaaclab.sim.visualizers import NewtonVisualizerCfg + + if env_cfg.sim.visualizers is None: + # No visualizers in config - use default Newton visualizer + env_cfg.sim.visualizers = NewtonVisualizerCfg(enabled=True) + else: + # Enable configured visualizer(s) + if isinstance(env_cfg.sim.visualizers, list): + for viz_cfg in env_cfg.sim.visualizers: + viz_cfg.enabled = True + else: + env_cfg.sim.visualizers.enabled = True # directory for logging into run_info = datetime.now().strftime("%Y-%m-%d_%H-%M-%S") diff --git a/scripts/reinforcement_learning/skrl/play.py b/scripts/reinforcement_learning/skrl/play.py index 252b3b3bc91..3cf9faba914 100644 --- a/scripts/reinforcement_learning/skrl/play.py +++ b/scripts/reinforcement_learning/skrl/play.py @@ -46,7 +46,12 @@ help="The RL algorithm used for training the skrl agent.", ) parser.add_argument("--real-time", action="store_true", default=False, help="Run in real-time, if possible.") -parser.add_argument("--newton_visualizer", action="store_true", default=False, help="Enable Newton rendering.") +parser.add_argument( + "--visualize", + action="store_true", + default=False, + help="Launch visualizer(s). Uses visualizers defined in environment config, or defaults to Newton OpenGL if none configured.", +) # append AppLauncher cli args AppLauncher.add_app_launcher_args(parser) @@ -116,8 +121,22 @@ def main(): device=args_cli.device, num_envs=args_cli.num_envs, use_fabric=not args_cli.disable_fabric, - newton_visualizer=args_cli.newton_visualizer, ) + + # handle visualizer launch + if args_cli.visualize: + from isaaclab.sim.visualizers import NewtonVisualizerCfg + + if env_cfg.sim.visualizers is None: + # No visualizers in config - use default Newton visualizer + env_cfg.sim.visualizers = NewtonVisualizerCfg(enabled=True) + else: + # Enable configured visualizer(s) + if isinstance(env_cfg.sim.visualizers, list): + for viz_cfg in env_cfg.sim.visualizers: + viz_cfg.enabled = True + else: + env_cfg.sim.visualizers.enabled = True try: experiment_cfg = load_cfg_from_registry(task_name, f"skrl_{algorithm}_cfg_entry_point") except ValueError: diff --git a/scripts/reinforcement_learning/skrl/train.py b/scripts/reinforcement_learning/skrl/train.py index d59b2cc45d7..6ef1a8cb145 100644 --- a/scripts/reinforcement_learning/skrl/train.py +++ b/scripts/reinforcement_learning/skrl/train.py @@ -44,7 +44,12 @@ choices=["AMP", "PPO", "IPPO", "MAPPO"], help="The RL algorithm used for training the skrl agent.", ) -parser.add_argument("--newton_visualizer", action="store_true", default=False, help="Enable Newton rendering.") +parser.add_argument( + "--visualize", + action="store_true", + default=False, + help="Launch visualizer(s). Uses visualizers defined in environment config, or defaults to Newton OpenGL if none configured.", +) # append AppLauncher cli args AppLauncher.add_app_launcher_args(parser) @@ -113,7 +118,21 @@ def main(env_cfg: ManagerBasedRLEnvCfg | DirectRLEnvCfg, agent_cfg: dict): # override configurations with non-hydra CLI arguments env_cfg.scene.num_envs = args_cli.num_envs if args_cli.num_envs is not None else env_cfg.scene.num_envs env_cfg.sim.device = args_cli.device if args_cli.device is not None else env_cfg.sim.device - env_cfg.sim.enable_newton_rendering = args_cli.newton_visualizer + + # handle visualizer launch + if args_cli.visualize: + from isaaclab.sim.visualizers import NewtonVisualizerCfg + + if env_cfg.sim.visualizers is None: + # No visualizers in config - use default Newton visualizer + env_cfg.sim.visualizers = NewtonVisualizerCfg(enabled=True) + else: + # Enable configured visualizer(s) + if isinstance(env_cfg.sim.visualizers, list): + for viz_cfg in env_cfg.sim.visualizers: + viz_cfg.enabled = True + else: + env_cfg.sim.visualizers.enabled = True # multi-gpu training config if args_cli.distributed: diff --git a/scripts/sim2sim_transfer/rsl_rl_transfer.py b/scripts/sim2sim_transfer/rsl_rl_transfer.py index d9b546ffd6f..20295d29eb5 100644 --- a/scripts/sim2sim_transfer/rsl_rl_transfer.py +++ b/scripts/sim2sim_transfer/rsl_rl_transfer.py @@ -29,7 +29,12 @@ help="Use the pre-trained checkpoint from Nucleus.", ) parser.add_argument("--real-time", action="store_true", default=False, help="Run in real-time, if possible.") -parser.add_argument("--newton_visualizer", action="store_true", default=False, help="Enable Newton rendering.") +parser.add_argument( + "--visualize", + action="store_true", + default=False, + help="Launch visualizer(s). Uses visualizers defined in environment config, or defaults to Newton OpenGL if none configured.", +) # Joint ordering arguments parser.add_argument( "--policy_transfer_file", @@ -147,8 +152,22 @@ def main(): device=args_cli.device, num_envs=args_cli.num_envs, use_fabric=not args_cli.disable_fabric, - newton_visualizer=args_cli.newton_visualizer, ) + + # handle visualizer launch + if args_cli.visualize: + from isaaclab.sim.visualizers import NewtonVisualizerCfg + + if env_cfg.sim.visualizers is None: + # No visualizers in config - use default Newton visualizer + env_cfg.sim.visualizers = NewtonVisualizerCfg(enabled=True) + else: + # Enable configured visualizer(s) + if isinstance(env_cfg.sim.visualizers, list): + for viz_cfg in env_cfg.sim.visualizers: + viz_cfg.enabled = True + else: + env_cfg.sim.visualizers.enabled = True agent_cfg: RslRlOnPolicyRunnerCfg = cli_args.parse_rsl_rl_cfg(task_name, args_cli) # specify directory for logging experiments diff --git a/source/isaaclab/isaaclab/sim/__init__.py b/source/isaaclab/isaaclab/sim/__init__.py index 6819cacf87b..b97f9f41382 100644 --- a/source/isaaclab/isaaclab/sim/__init__.py +++ b/source/isaaclab/isaaclab/sim/__init__.py @@ -27,6 +27,7 @@ """ from .converters import * # noqa: F401, F403 +from .scene_data_providers import NewtonSceneDataProvider, SceneDataProvider # noqa: F401, F403 from .schemas import * # noqa: F401, F403 from .simulation_cfg import RenderCfg, SimulationCfg # noqa: F401, F403 from .simulation_context import SimulationContext, build_simulation_context # noqa: F401, F403 diff --git a/source/isaaclab/isaaclab/sim/_impl/newton_manager_cfg.py b/source/isaaclab/isaaclab/sim/_impl/newton_manager_cfg.py index 02523192c0b..c79a9036250 100644 --- a/source/isaaclab/isaaclab/sim/_impl/newton_manager_cfg.py +++ b/source/isaaclab/isaaclab/sim/_impl/newton_manager_cfg.py @@ -13,10 +13,6 @@ class NewtonCfg: """Configuration for Newton-related parameters. These parameters are used to configure the Newton physics simulation. - - Note: - Visualizer-related settings have been moved to NewtonVisualizerCfg in - isaaclab.sim.visualizers.newton_visualizer_cfg. """ num_substeps: int = 1 diff --git a/source/isaaclab/isaaclab/sim/scene_data_providers/__init__.py b/source/isaaclab/isaaclab/sim/scene_data_providers/__init__.py new file mode 100644 index 00000000000..6cb665547a4 --- /dev/null +++ b/source/isaaclab/isaaclab/sim/scene_data_providers/__init__.py @@ -0,0 +1,23 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers. +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Sub-package for scene data provider implementations. + +This sub-package contains the abstract base class and concrete implementations +for providing scene data from various physics backends (Newton, PhysX, etc.) +to visualizers and renderers. + +The scene data provider abstraction allows visualizers and renderers to work +with any physics backend without directly coupling to specific backend implementations. +""" + +from .scene_data_provider import SceneDataProvider +from .newton_scene_data_provider import NewtonSceneDataProvider + +__all__ = [ + "SceneDataProvider", + "NewtonSceneDataProvider", +] + diff --git a/source/isaaclab/isaaclab/sim/scene_data_providers/newton_scene_data_provider.py b/source/isaaclab/isaaclab/sim/scene_data_providers/newton_scene_data_provider.py new file mode 100644 index 00000000000..f6ee83a6520 --- /dev/null +++ b/source/isaaclab/isaaclab/sim/scene_data_providers/newton_scene_data_provider.py @@ -0,0 +1,85 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers. +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Newton-specific scene data provider implementation.""" + +from __future__ import annotations + +from typing import TYPE_CHECKING, Any + +from .scene_data_provider import SceneDataProvider + +if TYPE_CHECKING: + from pxr import Usd + + +class NewtonSceneDataProvider(SceneDataProvider): + """Scene data provider for Newton physics backend. + + This class provides access to Newton physics data without directly exposing + the NewtonManager to downstream consumers. + """ + + def __init__(self, usd_stage: Usd.Stage | None = None): + """Initialize the Newton scene data provider. + + Args: + usd_stage: USD stage reference, if available. + """ + self._usd_stage = usd_stage + + def get_model(self) -> Any | None: + """Get the Newton physics model. + + Returns: + newton.Model instance, or None if not initialized. + """ + from isaaclab.sim._impl.newton_manager import NewtonManager + + return NewtonManager._model + + def get_state(self) -> Any | None: + """Get the current Newton physics state. + + Returns: + newton.State instance, or None if not initialized. + """ + from isaaclab.sim._impl.newton_manager import NewtonManager + + return NewtonManager._state_0 + + def get_usd_stage(self) -> Usd.Stage | None: + """Get the USD stage. + + Returns: + USD stage, or None if not available. + """ + return self._usd_stage + + def get_metadata(self) -> dict[str, Any]: + """Get Newton-specific metadata. + + Returns: + Dictionary containing: + - "physics_backend": "newton" + - "gravity_vector": tuple[float, float, float] + - "clone_physics_only": bool + """ + from isaaclab.sim._impl.newton_manager import NewtonManager + + return { + "physics_backend": "newton", + "gravity_vector": NewtonManager._gravity_vector, + "clone_physics_only": NewtonManager._clone_physics_only, + } + + def update_stage(self, usd_stage: Usd.Stage | None) -> None: + """Update the USD stage reference. + + Args: + usd_stage: New USD stage reference. + """ + self._usd_stage = usd_stage + diff --git a/source/isaaclab/isaaclab/sim/scene_data_providers/scene_data_provider.py b/source/isaaclab/isaaclab/sim/scene_data_providers/scene_data_provider.py new file mode 100644 index 00000000000..2ab4c632e70 --- /dev/null +++ b/source/isaaclab/isaaclab/sim/scene_data_providers/scene_data_provider.py @@ -0,0 +1,84 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers. +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Scene data provider abstraction for physics backends.""" + +from __future__ import annotations + +from abc import ABC, abstractmethod +from typing import TYPE_CHECKING, Any + +if TYPE_CHECKING: + from pxr import Usd + + +class SceneDataProvider(ABC): + """Abstract base class for providing scene data from physics backends to visualizers and renderers. + + This abstraction allows visualizers and renderers to work with any physics backend (Newton, PhysX, etc.) + without directly coupling to specific physics manager implementations. + """ + + @abstractmethod + def get_model(self) -> Any | None: + """Get the physics model. + + Returns: + Physics model object, or None if not available. The type depends on the backend + (e.g., newton.Model for Newton backend). + """ + pass + + @abstractmethod + def get_state(self) -> Any | None: + """Get the current physics state. + + Returns: + Physics state object, or None if not available. The type depends on the backend + (e.g., newton.State for Newton backend). + """ + pass + + @abstractmethod + def get_usd_stage(self) -> Usd.Stage | None: + """Get the USD stage. + + Returns: + USD stage, or None if not available. + """ + pass + + def get_metadata(self) -> dict[str, Any]: + """Get additional metadata about the scene. + + Returns: + Dictionary containing optional metadata such as: + - "physics_backend": str (e.g., "newton", "physx") + - "num_envs": int + - "device": str + - etc. + """ + return {} + + def get_scene_data(self) -> dict[str, Any]: + """Get all available scene data as a dictionary. + + This is a convenience method that collects all scene data into a single dict. + Individual visualizers can extract what they need. + + Returns: + Dictionary containing all available scene data: + - "model": Physics model + - "state": Physics state + - "usd_stage": USD stage + - "metadata": Additional metadata + """ + return { + "model": self.get_model(), + "state": self.get_state(), + "usd_stage": self.get_usd_stage(), + "metadata": self.get_metadata(), + } + diff --git a/source/isaaclab/isaaclab/sim/simulation_context.py b/source/isaaclab/isaaclab/sim/simulation_context.py index 9664c44da99..c4b6621d305 100644 --- a/source/isaaclab/isaaclab/sim/simulation_context.py +++ b/source/isaaclab/isaaclab/sim/simulation_context.py @@ -30,12 +30,13 @@ from pxr import Usd from isaaclab.sim._impl.newton_manager import NewtonManager +from isaaclab.sim.scene_data_providers import NewtonSceneDataProvider, SceneDataProvider from isaaclab.sim.utils import create_new_stage_in_memory, use_stage from .simulation_cfg import SimulationCfg from .spawners import DomeLightCfg, GroundPlaneCfg from .utils import bind_physics_material -from .visualizers import Visualizer, NewtonVisualizer, NewtonVisualizerCfg +from .visualizers import Visualizer class SimulationContext(_SimulationContext): @@ -256,6 +257,9 @@ def __init__(self, cfg: SimulationCfg | None = None): # initialize visualizers self._visualizers: list[Visualizer] = [] self._visualizer_step_counter = 0 + + # Scene data provider for visualizers and renderers (initialized after stage is available) + self._scene_provider: SceneDataProvider | None = None # flag for skipping prim deletion callback # when stage in memory is attached @@ -300,6 +304,9 @@ def __init__(self, cfg: SimulationCfg | None = None): NewtonManager._clone_physics_only = ( self.render_mode == self.RenderMode.NO_GUI_OR_RENDERING or self.render_mode == self.RenderMode.NO_RENDERING ) + + # Initialize scene data provider now that stage is available + self._scene_provider = NewtonSceneDataProvider(self.stage) def _apply_physics_settings(self): """Sets various carb physics settings.""" @@ -563,32 +570,38 @@ def initialize_visualizers(self) -> None: # Create and initialize each visualizer for viz_cfg in visualizer_cfgs: try: - # Create visualizer instance based on config type - if isinstance(viz_cfg, NewtonVisualizerCfg): - visualizer = NewtonVisualizer(viz_cfg) - else: - # Skip unsupported visualizer types for now + # Use factory pattern to create visualizer from config + visualizer = viz_cfg.create_visualizer() + + # Get initial scene data from the scene provider + if self._scene_provider is None: omni.log.warn( - f"Visualizer type '{type(viz_cfg).__name__}' is not yet implemented. Skipping." + f"Scene provider not initialized yet for visualizer '{viz_cfg.visualizer_type}'. " + "Visualizer will be initialized later." ) continue - - # Initialize with Newton model if available - if NewtonManager._model is not None: - scene = { - "model": NewtonManager._model, - "state": NewtonManager._state_0, - } - visualizer.initialize(scene) + + scene_data = self._scene_provider.get_scene_data() + + # Check if we have the minimum required data (physics model) + if scene_data.get("model") is not None: + visualizer.initialize(scene_data) self._visualizers.append(visualizer) - omni.log.info(f"Initialized visualizer: {type(visualizer).__name__}") + omni.log.info( + f"Initialized visualizer: {type(visualizer).__name__} " + f"(type: {viz_cfg.visualizer_type})" + ) else: omni.log.warn( - "Newton model not available yet. Visualizer will be initialized later." + f"Physics model not available yet for visualizer '{viz_cfg.visualizer_type}'. " + "Visualizer will be initialized later." ) except Exception as e: - omni.log.error(f"Failed to initialize visualizer '{type(viz_cfg).__name__}': {e}") + omni.log.error( + f"Failed to initialize visualizer '{viz_cfg.visualizer_type}' " + f"({type(viz_cfg).__name__}): {e}" + ) def step_visualizers(self, dt: float) -> None: """Update all active visualizers. @@ -616,20 +629,15 @@ def step_visualizers(self, dt: float) -> None: # Handle training pause - block until resumed while visualizer.is_training_paused() and visualizer.is_running(): - if isinstance(visualizer, NewtonVisualizer): - # Update state before rendering during pause - visualizer.update_state(NewtonManager._state_0) - visualizer.step(0.0) # Step with 0 dt during pause + # Step with 0 dt during pause, pass scene provider for state updates + visualizer.step(0.0, self._scene_provider) # Skip rendering if visualizer has rendering paused if visualizer.is_rendering_paused(): continue - # Normal step: update state and visualizer - if isinstance(visualizer, NewtonVisualizer): - visualizer.update_state(NewtonManager._state_0) - - visualizer.step(dt) + # Normal step: pass dt and scene provider so visualizer can pull latest state + visualizer.step(dt, self._scene_provider) except Exception as e: omni.log.error(f"Error stepping visualizer '{type(visualizer).__name__}': {e}") diff --git a/source/isaaclab/isaaclab/sim/visualizers/__init__.py b/source/isaaclab/isaaclab/sim/visualizers/__init__.py index 0814b88a412..2a7e8ff9ae8 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/__init__.py +++ b/source/isaaclab/isaaclab/sim/visualizers/__init__.py @@ -13,15 +13,36 @@ - Newton OpenGL Visualizer: Lightweight OpenGL-based visualizer - Omniverse Visualizer: High-fidelity Omniverse-based visualizer (coming soon) - Rerun Visualizer: Web-based visualizer using the rerun library (coming soon) + +Visualizer Registry +------------------- +This module uses a registry pattern to decouple visualizer instantiation from specific types. +Visualizer implementations can register themselves using the `register_visualizer` decorator, +and configs can create visualizers via the `create_visualizer()` factory method. """ +from __future__ import annotations + +from typing import TYPE_CHECKING, Any + +if TYPE_CHECKING: + from typing import Type + +# Import base classes first from .visualizer import Visualizer from .visualizer_cfg import VisualizerCfg -from .newton_visualizer import NewtonVisualizer + +# Import config classes (no circular dependency) from .newton_visualizer_cfg import NewtonVisualizerCfg from .ov_visualizer_cfg import OVVisualizerCfg from .rerun_visualizer_cfg import RerunVisualizerCfg +# Import visualizer implementations +from .newton_visualizer import NewtonVisualizer + +# Global registry for visualizer types (defined after Visualizer import) +_VISUALIZER_REGISTRY: dict[str, Any] = {} + __all__ = [ "Visualizer", "VisualizerCfg", @@ -29,6 +50,48 @@ "NewtonVisualizerCfg", "OVVisualizerCfg", "RerunVisualizerCfg", + "register_visualizer", + "get_visualizer_class", ] +def register_visualizer(name: str): + """Decorator to register a visualizer class with the given name. + + This allows visualizer configs to create instances without hard-coded type checking. + + Args: + name: Unique identifier for this visualizer type (e.g., "newton", "rerun", "omniverse"). + + Example: + >>> @register_visualizer("newton") + >>> class NewtonVisualizer(Visualizer): + >>> pass + """ + + def decorator(cls: Type[Visualizer]) -> Type[Visualizer]: + if name in _VISUALIZER_REGISTRY: + raise ValueError(f"Visualizer '{name}' is already registered!") + _VISUALIZER_REGISTRY[name] = cls + return cls + + return decorator + + +def get_visualizer_class(name: str) -> Type[Visualizer] | None: + """Get a registered visualizer class by name. + + Args: + name: Visualizer type name. + + Returns: + Visualizer class, or None if not found. + """ + return _VISUALIZER_REGISTRY.get(name) + + +# Register built-in visualizers +# Note: Registration happens here to avoid circular imports +_VISUALIZER_REGISTRY["newton"] = NewtonVisualizer + + diff --git a/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py b/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py index ac9ed2c217c..004b2ccf574 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py +++ b/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py @@ -7,12 +7,17 @@ from __future__ import annotations +from typing import TYPE_CHECKING, Any + import warp as wp from newton.viewer import ViewerGL from .newton_visualizer_cfg import NewtonVisualizerCfg from .visualizer import Visualizer +if TYPE_CHECKING: + from isaaclab.sim.scene_data_providers import SceneDataProvider + class NewtonViewerGL(ViewerGL): """Training-aware viewer that adds a separate pause for simulation/training. @@ -41,12 +46,8 @@ def is_training_paused(self) -> bool: """Check if training is paused.""" return self._paused_training - def is_paused(self) -> bool: - """Check if rendering is paused.""" - return self._paused_rendering - def is_rendering_paused(self) -> bool: - """Check if rendering is paused (alias for is_paused for consistency).""" + """Check if rendering is paused.""" return self._paused_rendering def set_visualizer_update_frequency(self, frequency: int) -> None: @@ -262,6 +263,9 @@ class NewtonVisualizer(Visualizer): fast visualization of simulations. It includes IsaacLab-specific features like training controls, rendering pause, and update frequency adjustment. + This class is registered with the visualizer registry as "newton" and can be + instantiated via NewtonVisualizerCfg.create_visualizer(). + Args: cfg: Configuration for the Newton visualizer. """ @@ -275,27 +279,24 @@ def __init__(self, cfg: NewtonVisualizerCfg): self._model = None self._state = None - def initialize(self, scene) -> None: + def initialize(self, scene_data: dict[str, Any] | None = None) -> None: """Initialize the Newton visualizer with the simulation scene. Args: - scene: Dictionary containing 'model' and 'state' for Newton simulation, - or the Newton Model object directly. + scene_data: Optional dictionary containing initial scene data. Expected keys: + - "model": Newton Model object (required) + - "state": Newton State object (optional) """ if self._is_initialized: return - # Extract model and state from scene - if isinstance(scene, dict): - self._model = scene.get("model") - self._state = scene.get("state") - else: - # Assume scene is the Newton Model - self._model = scene - self._state = None - + # Extract model and state from scene data + if scene_data is not None: + self._model = scene_data.get("model") + self._state = scene_data.get("state") + if self._model is None: - raise ValueError("Newton visualizer requires a Newton Model to be provided in the scene") + raise ValueError("Newton visualizer requires a Newton Model to be provided in scene_data['model']") # Create the viewer self._viewer = NewtonViewerGL( @@ -334,11 +335,13 @@ def initialize(self, scene) -> None: self._is_initialized = True - def step(self, dt: float) -> None: + def step(self, dt: float, scene_provider: SceneDataProvider | None = None) -> None: """Update the visualizer for one simulation step. Args: dt: Time step in seconds since last visualization update. + scene_provider: Provider for accessing current scene data. The visualizer + will pull the latest Newton state from this provider. Note: Pause handling (training and rendering) is managed by SimulationContext. @@ -352,6 +355,10 @@ def step(self, dt: float) -> None: # Update simulation time self._sim_time += dt + # Get the latest state from the scene provider + if scene_provider is not None: + self._state = scene_provider.get_state() + # Render the current frame # Note: We always call begin_frame/end_frame to maintain ImGui state # The update frequency is handled internally by the viewer diff --git a/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer_cfg.py b/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer_cfg.py index e9304f9eca9..dadf5ad88ef 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer_cfg.py +++ b/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer_cfg.py @@ -33,6 +33,10 @@ class NewtonVisualizerCfg(VisualizerCfg): not visual shapes. """ + # Visualizer type identifier + visualizer_type: str = "newton" + """Type identifier for Newton visualizer. Used by the factory pattern.""" + # Override defaults for Newton visualizer camera_position: tuple[float, float, float] = (10.0, 0.0, 3.0) """Initial position of the camera. Default is (10.0, 0.0, 3.0).""" diff --git a/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer.py b/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer.py index e69de29bb2d..095a8b7de49 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer.py +++ b/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer.py @@ -0,0 +1,18 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Omniverse Visualizer implementation.""" + +from __future__ import annotations + +from .ov_visualizer_cfg import OVVisualizerCfg +from .visualizer import Visualizer + + +class OmniverseVisualizer(Visualizer): + """Omniverse Visualizer implementation.""" + def __init__(self, cfg: OVVisualizerCfg): + super().__init__(cfg) + # stub for now \ No newline at end of file diff --git a/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer.py b/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer.py index e69de29bb2d..7758a938d6e 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer.py +++ b/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer.py @@ -0,0 +1,18 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Omniverse Visualizer implementation.""" + +from __future__ import annotations + +from .ov_visualizer_cfg import RerunVisualizerCfg +from .visualizer import Visualizer + + +class RerunVisualizer(Visualizer): + """Omniverse Visualizer implementation.""" + def __init__(self, cfg: RerunVisualizerCfg): + super().__init__(cfg) + # stub for now \ No newline at end of file diff --git a/source/isaaclab/isaaclab/sim/visualizers/visualizer.py b/source/isaaclab/isaaclab/sim/visualizers/visualizer.py index e118be751f1..271da4da78a 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/visualizer.py +++ b/source/isaaclab/isaaclab/sim/visualizers/visualizer.py @@ -8,9 +8,11 @@ from __future__ import annotations from abc import ABC, abstractmethod -from typing import TYPE_CHECKING +from typing import TYPE_CHECKING, Any if TYPE_CHECKING: + from isaaclab.sim.scene_data_providers import SceneDataProvider + from .visualizer_cfg import VisualizerCfg @@ -42,27 +44,34 @@ def __init__(self, cfg: VisualizerCfg): self._is_closed = False @abstractmethod - def initialize(self, scene) -> None: + def initialize(self, scene_data: dict[str, Any] | None = None) -> None: """Initialize the visualizer with the simulation scene. This method is called once after the simulation scene is created and before the simulation starts. It should set up any necessary resources for visualization. Args: - scene: The simulation scene to visualize. This could be a Newton Model, - a USD stage, or other scene representation depending on the backend. + scene_data: Optional dictionary containing initial scene data. The contents + depend on what's available at initialization time. May include: + - "model": Physics model object + - "state": Initial physics state + - "usd_stage": USD stage + The visualizer should handle None or missing keys gracefully. """ pass @abstractmethod - def step(self, dt: float) -> None: + def step(self, dt: float, scene_provider: SceneDataProvider | None = None) -> None: """Update the visualizer for one simulation step. This method is called each simulation step to update the visualization. - The frequency of calls is controlled by the update_frequency parameter in the config. + The visualizer should pull any needed data from the scene_provider. Args: dt: Time step in seconds since last visualization update. + scene_provider: Provider for accessing current scene data (physics state, USD stage, etc.). + Visualizers should query this for updated data rather than directly + accessing physics managers. May be None if no scene data is available yet. """ pass diff --git a/source/isaaclab/isaaclab/sim/visualizers/visualizer_cfg.py b/source/isaaclab/isaaclab/sim/visualizers/visualizer_cfg.py index fce04f0c786..76d54673105 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/visualizer_cfg.py +++ b/source/isaaclab/isaaclab/sim/visualizers/visualizer_cfg.py @@ -5,10 +5,15 @@ """Base configuration for visualizers.""" -from typing import Literal +from __future__ import annotations + +from typing import TYPE_CHECKING, Literal from isaaclab.utils import configclass +if TYPE_CHECKING: + from .visualizer import Visualizer + @configclass class VisualizerCfg: @@ -22,6 +27,13 @@ class VisualizerCfg: configuration parameters. """ + visualizer_type: str = "base" + """Type identifier for this visualizer (e.g., 'newton', 'rerun', 'omniverse'). + + This is used by the factory pattern to instantiate the correct visualizer class. + Subclasses should override this with their specific type identifier. + """ + enabled: bool = False """Whether the visualizer is enabled. Default is False.""" @@ -84,6 +96,30 @@ def get_visualizer_type(self) -> str: Returns: String identifier for the visualizer type. """ - return self.__class__.__name__.replace("VisualizerCfg", "").replace("Cfg", "") + return self.visualizer_type + + def create_visualizer(self) -> Visualizer: + """Factory method to create a visualizer instance from this configuration. + + This method uses the visualizer registry to instantiate the appropriate + visualizer class based on the `visualizer_type` field. + + Returns: + Visualizer instance configured with this config. + + Raises: + ValueError: If the visualizer type is not registered. + """ + # Import here to avoid circular imports + from . import get_visualizer_class + + visualizer_class = get_visualizer_class(self.visualizer_type) + if visualizer_class is None: + raise ValueError( + f"Visualizer type '{self.visualizer_type}' is not registered. " + f"Make sure the visualizer module is imported." + ) + + return visualizer_class(self) diff --git a/source/isaaclab_tasks/isaaclab_tasks/utils/parse_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/utils/parse_cfg.py index 755c3ad0acf..a07befbd3f9 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/utils/parse_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/utils/parse_cfg.py @@ -136,15 +136,6 @@ def parse_env_cfg( Raises: RuntimeError: If the configuration for the task is not a class. We assume users always use a class for the environment configuration. - - Note: - To enable visualizers, set them directly in the environment configuration using - SimulationCfg.visualizers. For example: - - .. code-block:: python - - from isaaclab.sim.visualizers import NewtonVisualizerCfg - cfg.sim.visualizers = NewtonVisualizerCfg(enabled=True) """ # load the default configuration cfg = load_cfg_from_registry(task_name.split(":")[-1], "env_cfg_entry_point") From a1e8ec221a855436d68bf3d621f3f988178646e9 Mon Sep 17 00:00:00 2001 From: mtrepte Date: Tue, 11 Nov 2025 23:13:17 -0800 Subject: [PATCH 04/24] bug fix --- .../newton_scene_data_provider.py | 2 ++ .../isaaclab/sim/visualizers/newton_visualizer.py | 13 +++++++++---- 2 files changed, 11 insertions(+), 4 deletions(-) diff --git a/source/isaaclab/isaaclab/sim/scene_data_providers/newton_scene_data_provider.py b/source/isaaclab/isaaclab/sim/scene_data_providers/newton_scene_data_provider.py index f6ee83a6520..1966ba7a33b 100644 --- a/source/isaaclab/isaaclab/sim/scene_data_providers/newton_scene_data_provider.py +++ b/source/isaaclab/isaaclab/sim/scene_data_providers/newton_scene_data_provider.py @@ -64,6 +64,7 @@ def get_metadata(self) -> dict[str, Any]: Returns: Dictionary containing: - "physics_backend": "newton" + - "num_envs": int - "gravity_vector": tuple[float, float, float] - "clone_physics_only": bool """ @@ -71,6 +72,7 @@ def get_metadata(self) -> dict[str, Any]: return { "physics_backend": "newton", + "num_envs": NewtonManager._num_envs if NewtonManager._num_envs is not None else 0, "gravity_vector": NewtonManager._gravity_vector, "clone_physics_only": NewtonManager._clone_physics_only, } diff --git a/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py b/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py index 004b2ccf574..52368afa4fd 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py +++ b/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py @@ -29,13 +29,14 @@ class NewtonViewerGL(ViewerGL): The training pause can be toggled from the UI via a button and optionally via the 'T' key. """ - def __init__(self, *args, train_mode: bool = True, **kwargs): + def __init__(self, *args, train_mode: bool = True, metadata: dict | None = None, **kwargs): super().__init__(*args, **kwargs) self._paused_training: bool = False self._paused_rendering: bool = False self._fallback_draw_controls: bool = False self._is_train_mode: bool = train_mode self._visualizer_update_frequency: int = 1 + self._metadata = metadata or {} try: self.register_ui_callback(self._render_training_controls, position="side") @@ -174,7 +175,8 @@ def _render_left_panel(self): imgui.set_next_item_open(True, imgui.Cond_.appearing) if imgui.collapsing_header("Model Information", flags=header_flags): imgui.separator() - imgui.text(f"Environments: {self.model.num_envs}") + num_envs = self._metadata.get("num_envs", 0) + imgui.text(f"Environments: {num_envs}") axis_names = ["X", "Y", "Z"] imgui.text(f"Up Axis: {axis_names[self.model.up_axis]}") gravity = wp.to_torch(self.model.gravity)[0] @@ -290,19 +292,22 @@ def initialize(self, scene_data: dict[str, Any] | None = None) -> None: if self._is_initialized: return - # Extract model and state from scene data + # Extract model, state, and metadata from scene data + metadata = {} if scene_data is not None: self._model = scene_data.get("model") self._state = scene_data.get("state") + metadata = scene_data.get("metadata", {}) if self._model is None: raise ValueError("Newton visualizer requires a Newton Model to be provided in scene_data['model']") - # Create the viewer + # Create the viewer with metadata self._viewer = NewtonViewerGL( width=self.cfg.window_width, height=self.cfg.window_height, train_mode=self.cfg.train_mode, + metadata=metadata, ) # Set the model From c927485795e89a9332d9dc40a248452b5227b8a4 Mon Sep 17 00:00:00 2001 From: mtrepte Date: Tue, 11 Nov 2025 23:33:05 -0800 Subject: [PATCH 05/24] clean --- scripts/environments/random_agent.py | 16 ++------- scripts/environments/zero_agent.py | 16 ++------- .../reinforcement_learning/rl_games/play.py | 22 +----------- .../reinforcement_learning/rl_games/train.py | 16 ++------- scripts/reinforcement_learning/rsl_rl/play.py | 33 ++--------------- .../reinforcement_learning/rsl_rl/train.py | 16 ++------- scripts/reinforcement_learning/sb3/play.py | 22 +----------- scripts/reinforcement_learning/sb3/train.py | 16 ++------- scripts/reinforcement_learning/skrl/play.py | 22 +----------- scripts/reinforcement_learning/skrl/train.py | 16 ++------- scripts/sim2sim_transfer/rsl_rl_transfer.py | 16 ++------- source/isaaclab/isaaclab/sim/__init__.py | 2 +- .../isaaclab/sim/simulation_context.py | 36 +++++++++++++++++++ .../isaaclab_tasks/utils/parse_cfg.py | 10 ++++++ 14 files changed, 74 insertions(+), 185 deletions(-) diff --git a/scripts/environments/random_agent.py b/scripts/environments/random_agent.py index 653b2be5ccf..dfb1302d3d5 100644 --- a/scripts/environments/random_agent.py +++ b/scripts/environments/random_agent.py @@ -59,20 +59,10 @@ def main(): use_fabric=not args_cli.disable_fabric, ) - # handle visualizer launch + # enable visualizers if requested if args_cli.visualize: - from isaaclab.sim.visualizers import NewtonVisualizerCfg - - if env_cfg.sim.visualizers is None: - # No visualizers in config - use default Newton visualizer - env_cfg.sim.visualizers = NewtonVisualizerCfg(enabled=True) - else: - # Enable configured visualizer(s) - if isinstance(env_cfg.sim.visualizers, list): - for viz_cfg in env_cfg.sim.visualizers: - viz_cfg.enabled = True - else: - env_cfg.sim.visualizers.enabled = True + import isaaclab.sim as sim_utils + sim_utils.enable_visualizers(env_cfg) # create environment env = gym.make(args_cli.task, cfg=env_cfg) diff --git a/scripts/environments/zero_agent.py b/scripts/environments/zero_agent.py index d2a3b64541e..5b690c7caaf 100644 --- a/scripts/environments/zero_agent.py +++ b/scripts/environments/zero_agent.py @@ -59,20 +59,10 @@ def main(): use_fabric=not args_cli.disable_fabric, ) - # handle visualizer launch + # enable visualizers if requested if args_cli.visualize: - from isaaclab.sim.visualizers import NewtonVisualizerCfg - - if env_cfg.sim.visualizers is None: - # No visualizers in config - use default Newton visualizer - env_cfg.sim.visualizers = NewtonVisualizerCfg(enabled=True) - else: - # Enable configured visualizer(s) - if isinstance(env_cfg.sim.visualizers, list): - for viz_cfg in env_cfg.sim.visualizers: - viz_cfg.enabled = True - else: - env_cfg.sim.visualizers.enabled = True + import isaaclab.sim as sim_utils + sim_utils.enable_visualizers(env_cfg) # create environment env = gym.make(args_cli.task, cfg=env_cfg) diff --git a/scripts/reinforcement_learning/rl_games/play.py b/scripts/reinforcement_learning/rl_games/play.py index 8cb49c7098c..189f89349e7 100644 --- a/scripts/reinforcement_learning/rl_games/play.py +++ b/scripts/reinforcement_learning/rl_games/play.py @@ -84,27 +84,7 @@ def main(): """Play with RL-Games agent.""" task_name = args_cli.task.split(":")[-1] # parse env configuration - env_cfg = parse_env_cfg( - args_cli.task, - device=args_cli.device, - num_envs=args_cli.num_envs, - use_fabric=not args_cli.disable_fabric, - ) - - # handle visualizer launch - if args_cli.visualize: - from isaaclab.sim.visualizers import NewtonVisualizerCfg - - if env_cfg.sim.visualizers is None: - # No visualizers in config - use default Newton visualizer - env_cfg.sim.visualizers = NewtonVisualizerCfg(enabled=True) - else: - # Enable configured visualizer(s) - if isinstance(env_cfg.sim.visualizers, list): - for viz_cfg in env_cfg.sim.visualizers: - viz_cfg.enabled = True - else: - env_cfg.sim.visualizers.enabled = True + env_cfg = parse_env_cfg(args_cli.task, device=args_cli.device, num_envs=args_cli.num_envs, use_fabric=not args_cli.disable_fabric, visualize=args_cli.visualize, train_mode=False) agent_cfg = load_cfg_from_registry(args_cli.task, "rl_games_cfg_entry_point") # specify directory for logging experiments diff --git a/scripts/reinforcement_learning/rl_games/train.py b/scripts/reinforcement_learning/rl_games/train.py index b12647306da..80a077eefa8 100644 --- a/scripts/reinforcement_learning/rl_games/train.py +++ b/scripts/reinforcement_learning/rl_games/train.py @@ -96,20 +96,10 @@ def main(env_cfg: ManagerBasedRLEnvCfg | DirectRLEnvCfg, agent_cfg: dict): env_cfg.scene.num_envs = args_cli.num_envs if args_cli.num_envs is not None else env_cfg.scene.num_envs env_cfg.sim.device = args_cli.device if args_cli.device is not None else env_cfg.sim.device - # handle visualizer launch + # enable visualizers if requested if args_cli.visualize: - from isaaclab.sim.visualizers import NewtonVisualizerCfg - - if env_cfg.sim.visualizers is None: - # No visualizers in config - use default Newton visualizer - env_cfg.sim.visualizers = NewtonVisualizerCfg(enabled=True) - else: - # Enable configured visualizer(s) - if isinstance(env_cfg.sim.visualizers, list): - for viz_cfg in env_cfg.sim.visualizers: - viz_cfg.enabled = True - else: - env_cfg.sim.visualizers.enabled = True + import isaaclab.sim as sim_utils + sim_utils.enable_visualizers(env_cfg) # randomly sample a seed if seed = -1 if args_cli.seed == -1: diff --git a/scripts/reinforcement_learning/rsl_rl/play.py b/scripts/reinforcement_learning/rsl_rl/play.py index f703524aec3..cf02ba60ea6 100644 --- a/scripts/reinforcement_learning/rsl_rl/play.py +++ b/scripts/reinforcement_learning/rsl_rl/play.py @@ -102,20 +102,10 @@ def main(env_cfg: ManagerBasedRLEnvCfg | DirectRLEnvCfg, agent_cfg: RslRlBaseRun env_cfg.seed = agent_cfg.seed env_cfg.sim.device = args_cli.device if args_cli.device is not None else env_cfg.sim.device - # handle visualizer launch + # enable visualizers if requested if args_cli.visualize: - from isaaclab.sim.visualizers import NewtonVisualizerCfg - - if env_cfg.sim.visualizers is None: - # No visualizers in config - use default Newton visualizer - env_cfg.sim.visualizers = NewtonVisualizerCfg(enabled=True) - else: - # Enable configured visualizer(s) - if isinstance(env_cfg.sim.visualizers, list): - for viz_cfg in env_cfg.sim.visualizers: - viz_cfg.enabled = True - else: - env_cfg.sim.visualizers.enabled = True + import isaaclab.sim as sim_utils + sim_utils.enable_visualizers(env_cfg, train_mode=False) # specify directory for logging experiments log_root_path = os.path.join("logs", "rsl_rl", agent_cfg.experiment_name) @@ -136,23 +126,6 @@ def main(env_cfg: ManagerBasedRLEnvCfg | DirectRLEnvCfg, agent_cfg: RslRlBaseRun # set the log directory for the environment (works for all environment types) env_cfg.log_dir = log_dir - # Set play mode for visualizers - if env_cfg.sim.visualizers is not None: - from isaaclab.sim.visualizers import NewtonVisualizerCfg - - if isinstance(env_cfg.sim.visualizers, list): - for viz_cfg in env_cfg.sim.visualizers: - viz_cfg.train_mode = False - elif isinstance(env_cfg.sim.visualizers, NewtonVisualizerCfg): - env_cfg.sim.visualizers.train_mode = False - else: - # Create newton_cfg if it doesn't exist - from isaaclab.sim._impl.newton_manager_cfg import NewtonCfg - - newton_cfg = NewtonCfg() - newton_cfg.visualizer_train_mode = False - env_cfg.sim.newton_cfg = newton_cfg - # create isaac environment env = gym.make(args_cli.task, cfg=env_cfg, render_mode="rgb_array" if args_cli.video else None) diff --git a/scripts/reinforcement_learning/rsl_rl/train.py b/scripts/reinforcement_learning/rsl_rl/train.py index 63e0dc1293c..380c1ae0b91 100644 --- a/scripts/reinforcement_learning/rsl_rl/train.py +++ b/scripts/reinforcement_learning/rsl_rl/train.py @@ -125,20 +125,10 @@ def main(env_cfg: ManagerBasedRLEnvCfg | DirectRLEnvCfg, agent_cfg: RslRlBaseRun env_cfg.seed = agent_cfg.seed env_cfg.sim.device = args_cli.device if args_cli.device is not None else env_cfg.sim.device - # handle visualizer launch + # enable visualizers if requested if args_cli.visualize: - from isaaclab.sim.visualizers import NewtonVisualizerCfg - - if env_cfg.sim.visualizers is None: - # No visualizers in config - use default Newton visualizer - env_cfg.sim.visualizers = NewtonVisualizerCfg(enabled=True) - else: - # Enable configured visualizer(s) - if isinstance(env_cfg.sim.visualizers, list): - for viz_cfg in env_cfg.sim.visualizers: - viz_cfg.enabled = True - else: - env_cfg.sim.visualizers.enabled = True + import isaaclab.sim as sim_utils + sim_utils.enable_visualizers(env_cfg) # multi-gpu training configuration if args_cli.distributed: diff --git a/scripts/reinforcement_learning/sb3/play.py b/scripts/reinforcement_learning/sb3/play.py index 09df5beba36..cb3473a29e3 100644 --- a/scripts/reinforcement_learning/sb3/play.py +++ b/scripts/reinforcement_learning/sb3/play.py @@ -87,27 +87,7 @@ def main(): """Play with stable-baselines agent.""" # parse configuration - env_cfg = parse_env_cfg( - args_cli.task, - device=args_cli.device, - num_envs=args_cli.num_envs, - use_fabric=not args_cli.disable_fabric, - ) - - # handle visualizer launch - if args_cli.visualize: - from isaaclab.sim.visualizers import NewtonVisualizerCfg - - if env_cfg.sim.visualizers is None: - # No visualizers in config - use default Newton visualizer - env_cfg.sim.visualizers = NewtonVisualizerCfg(enabled=True) - else: - # Enable configured visualizer(s) - if isinstance(env_cfg.sim.visualizers, list): - for viz_cfg in env_cfg.sim.visualizers: - viz_cfg.enabled = True - else: - env_cfg.sim.visualizers.enabled = True + env_cfg = parse_env_cfg(args_cli.task, device=args_cli.device, num_envs=args_cli.num_envs, use_fabric=not args_cli.disable_fabric, visualize=args_cli.visualize, train_mode=False) task_name = args_cli.task.split(":")[-1] train_task_name = task_name.replace("-Play", "") diff --git a/scripts/reinforcement_learning/sb3/train.py b/scripts/reinforcement_learning/sb3/train.py index a29a29e66bf..03ae5246269 100644 --- a/scripts/reinforcement_learning/sb3/train.py +++ b/scripts/reinforcement_learning/sb3/train.py @@ -119,20 +119,10 @@ def main(env_cfg: ManagerBasedRLEnvCfg | DirectRLEnvCfg, agent_cfg: dict): env_cfg.seed = agent_cfg["seed"] env_cfg.sim.device = args_cli.device if args_cli.device is not None else env_cfg.sim.device - # handle visualizer launch + # enable visualizers if requested if args_cli.visualize: - from isaaclab.sim.visualizers import NewtonVisualizerCfg - - if env_cfg.sim.visualizers is None: - # No visualizers in config - use default Newton visualizer - env_cfg.sim.visualizers = NewtonVisualizerCfg(enabled=True) - else: - # Enable configured visualizer(s) - if isinstance(env_cfg.sim.visualizers, list): - for viz_cfg in env_cfg.sim.visualizers: - viz_cfg.enabled = True - else: - env_cfg.sim.visualizers.enabled = True + import isaaclab.sim as sim_utils + sim_utils.enable_visualizers(env_cfg) # directory for logging into run_info = datetime.now().strftime("%Y-%m-%d_%H-%M-%S") diff --git a/scripts/reinforcement_learning/skrl/play.py b/scripts/reinforcement_learning/skrl/play.py index 3cf9faba914..54b93ec97f4 100644 --- a/scripts/reinforcement_learning/skrl/play.py +++ b/scripts/reinforcement_learning/skrl/play.py @@ -116,27 +116,7 @@ def main(): task_name = args_cli.task.split(":")[-1] # parse configuration - env_cfg = parse_env_cfg( - args_cli.task, - device=args_cli.device, - num_envs=args_cli.num_envs, - use_fabric=not args_cli.disable_fabric, - ) - - # handle visualizer launch - if args_cli.visualize: - from isaaclab.sim.visualizers import NewtonVisualizerCfg - - if env_cfg.sim.visualizers is None: - # No visualizers in config - use default Newton visualizer - env_cfg.sim.visualizers = NewtonVisualizerCfg(enabled=True) - else: - # Enable configured visualizer(s) - if isinstance(env_cfg.sim.visualizers, list): - for viz_cfg in env_cfg.sim.visualizers: - viz_cfg.enabled = True - else: - env_cfg.sim.visualizers.enabled = True + env_cfg = parse_env_cfg(args_cli.task, device=args_cli.device, num_envs=args_cli.num_envs, use_fabric=not args_cli.disable_fabric, visualize=args_cli.visualize, train_mode=False) try: experiment_cfg = load_cfg_from_registry(task_name, f"skrl_{algorithm}_cfg_entry_point") except ValueError: diff --git a/scripts/reinforcement_learning/skrl/train.py b/scripts/reinforcement_learning/skrl/train.py index 6ef1a8cb145..add4686603f 100644 --- a/scripts/reinforcement_learning/skrl/train.py +++ b/scripts/reinforcement_learning/skrl/train.py @@ -119,20 +119,10 @@ def main(env_cfg: ManagerBasedRLEnvCfg | DirectRLEnvCfg, agent_cfg: dict): env_cfg.scene.num_envs = args_cli.num_envs if args_cli.num_envs is not None else env_cfg.scene.num_envs env_cfg.sim.device = args_cli.device if args_cli.device is not None else env_cfg.sim.device - # handle visualizer launch + # enable visualizers if requested if args_cli.visualize: - from isaaclab.sim.visualizers import NewtonVisualizerCfg - - if env_cfg.sim.visualizers is None: - # No visualizers in config - use default Newton visualizer - env_cfg.sim.visualizers = NewtonVisualizerCfg(enabled=True) - else: - # Enable configured visualizer(s) - if isinstance(env_cfg.sim.visualizers, list): - for viz_cfg in env_cfg.sim.visualizers: - viz_cfg.enabled = True - else: - env_cfg.sim.visualizers.enabled = True + import isaaclab.sim as sim_utils + sim_utils.enable_visualizers(env_cfg) # multi-gpu training config if args_cli.distributed: diff --git a/scripts/sim2sim_transfer/rsl_rl_transfer.py b/scripts/sim2sim_transfer/rsl_rl_transfer.py index 20295d29eb5..63f92c2e3e7 100644 --- a/scripts/sim2sim_transfer/rsl_rl_transfer.py +++ b/scripts/sim2sim_transfer/rsl_rl_transfer.py @@ -154,20 +154,10 @@ def main(): use_fabric=not args_cli.disable_fabric, ) - # handle visualizer launch + # enable visualizers if requested if args_cli.visualize: - from isaaclab.sim.visualizers import NewtonVisualizerCfg - - if env_cfg.sim.visualizers is None: - # No visualizers in config - use default Newton visualizer - env_cfg.sim.visualizers = NewtonVisualizerCfg(enabled=True) - else: - # Enable configured visualizer(s) - if isinstance(env_cfg.sim.visualizers, list): - for viz_cfg in env_cfg.sim.visualizers: - viz_cfg.enabled = True - else: - env_cfg.sim.visualizers.enabled = True + import isaaclab.sim as sim_utils + sim_utils.enable_visualizers(env_cfg) agent_cfg: RslRlOnPolicyRunnerCfg = cli_args.parse_rsl_rl_cfg(task_name, args_cli) # specify directory for logging experiments diff --git a/source/isaaclab/isaaclab/sim/__init__.py b/source/isaaclab/isaaclab/sim/__init__.py index b97f9f41382..7186730171c 100644 --- a/source/isaaclab/isaaclab/sim/__init__.py +++ b/source/isaaclab/isaaclab/sim/__init__.py @@ -30,6 +30,6 @@ from .scene_data_providers import NewtonSceneDataProvider, SceneDataProvider # noqa: F401, F403 from .schemas import * # noqa: F401, F403 from .simulation_cfg import RenderCfg, SimulationCfg # noqa: F401, F403 -from .simulation_context import SimulationContext, build_simulation_context # noqa: F401, F403 +from .simulation_context import SimulationContext, build_simulation_context, enable_visualizers # noqa: F401, F403 from .spawners import * # noqa: F401, F403 from .utils import * # noqa: F401, F403 diff --git a/source/isaaclab/isaaclab/sim/simulation_context.py b/source/isaaclab/isaaclab/sim/simulation_context.py index c4b6621d305..3904906911b 100644 --- a/source/isaaclab/isaaclab/sim/simulation_context.py +++ b/source/isaaclab/isaaclab/sim/simulation_context.py @@ -1033,3 +1033,39 @@ def build_simulation_context( exception_to_raise = builtins.ISAACLAB_CALLBACK_EXCEPTION builtins.ISAACLAB_CALLBACK_EXCEPTION = None raise exception_to_raise + + +def enable_visualizers(env_cfg, train_mode: bool = True) -> None: + """Enable visualizers for an environment configuration. + + If no visualizers are configured, defaults to Newton OpenGL visualizer. + If visualizers are already configured, enables them. + + This is a utility function for use in scripts that want to enable visualization + based on command-line arguments. + + Args: + env_cfg: Environment configuration (DirectRLEnvCfg or ManagerBasedRLEnvCfg) to modify. + train_mode: Whether to run visualizers in training mode (True) or play/inference mode (False). + Default is True. + + Example: + >>> import isaaclab.sim as sim_utils + >>> if args_cli.visualize: + ... sim_utils.enable_visualizers(env_cfg) # For training + ... sim_utils.enable_visualizers(env_cfg, train_mode=False) # For play/inference + """ + from .visualizers import NewtonVisualizerCfg + + if env_cfg.sim.visualizers is None: + # No visualizers in config - use default Newton visualizer + env_cfg.sim.visualizers = NewtonVisualizerCfg(enabled=True, train_mode=train_mode) + else: + # Enable configured visualizer(s) + if isinstance(env_cfg.sim.visualizers, list): + for viz_cfg in env_cfg.sim.visualizers: + viz_cfg.enabled = True + viz_cfg.train_mode = train_mode + else: + env_cfg.sim.visualizers.enabled = True + env_cfg.sim.visualizers.train_mode = train_mode diff --git a/source/isaaclab_tasks/isaaclab_tasks/utils/parse_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/utils/parse_cfg.py index a07befbd3f9..b8f3357e7ea 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/utils/parse_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/utils/parse_cfg.py @@ -119,6 +119,8 @@ def parse_env_cfg( device: str = "cuda:0", num_envs: int | None = None, use_fabric: bool | None = None, + visualize: bool = False, + train_mode: bool = True, ) -> ManagerBasedRLEnvCfg | DirectRLEnvCfg: """Parse configuration for an environment and override based on inputs. @@ -129,6 +131,10 @@ def parse_env_cfg( use_fabric: Whether to enable/disable fabric interface. If false, all read/write operations go through USD. This slows down the simulation but allows seeing the changes in the USD through the USD stage. Defaults to None, in which case it is left unchanged. + visualize: Whether to launch visualizer(s). Uses visualizers defined in environment config, or defaults + to Newton OpenGL if none configured. Defaults to False. + train_mode: Whether to run visualizers in training mode (True) or play/inference mode (False). + Only applies if visualize is True. Defaults to True. Returns: The parsed configuration object. @@ -153,6 +159,10 @@ def parse_env_cfg( # number of environments if num_envs is not None: cfg.scene.num_envs = num_envs + # visualizer configuration + if visualize: + import isaaclab.sim as sim_utils + sim_utils.enable_visualizers(cfg, train_mode=train_mode) return cfg From 1b24ba5682dc757245af150bb8958bc39ece6390 Mon Sep 17 00:00:00 2001 From: mtrepte Date: Thu, 13 Nov 2025 14:49:51 -0800 Subject: [PATCH 06/24] wip --- .../isaaclab/isaaclab/sim/simulation_cfg.py | 7 +- .../isaaclab/sim/simulation_context.py | 28 +- .../isaaclab/sim/visualizers/__init__.py | 6 +- .../sim/visualizers/newton_visualizer.py | 35 +- .../isaaclab/sim/visualizers/ov_visualizer.py | 302 +++++++++++++++++- .../sim/visualizers/ov_visualizer_cfg.py | 166 ++-------- .../isaaclab/sim/visualizers/visualizer.py | 25 ++ 7 files changed, 402 insertions(+), 167 deletions(-) diff --git a/source/isaaclab/isaaclab/sim/simulation_cfg.py b/source/isaaclab/isaaclab/sim/simulation_cfg.py index 4e46f75fcff..a3ff7250f4f 100644 --- a/source/isaaclab/isaaclab/sim/simulation_cfg.py +++ b/source/isaaclab/isaaclab/sim/simulation_cfg.py @@ -15,7 +15,7 @@ from ._impl.newton_manager_cfg import NewtonCfg from .spawners.materials import RigidBodyMaterialCfg -from .visualizers import VisualizerCfg +from .visualizers import VisualizerCfg, NewtonVisualizerCfg, OVVisualizerCfg, RerunVisualizerCfg @configclass @@ -197,8 +197,9 @@ class SimulationCfg: render: RenderCfg = RenderCfg() """Render settings. Default is RenderCfg().""" - visualizers: list[VisualizerCfg] | VisualizerCfg | None = None - """Visualizer settings. Default is None (no visualizer). + # visualizers: list[VisualizerCfg] | VisualizerCfg | None = NewtonVisualizerCfg(enabled=True) + visualizers: list[VisualizerCfg] | VisualizerCfg | None = OVVisualizerCfg(enabled=True) + """Visualizer settings. Default is Newton (no visualizer). This field supports multiple visualizer backends for debug visualization and monitoring during simulation. It accepts: diff --git a/source/isaaclab/isaaclab/sim/simulation_context.py b/source/isaaclab/isaaclab/sim/simulation_context.py index 3904906911b..5eb886ba60c 100644 --- a/source/isaaclab/isaaclab/sim/simulation_context.py +++ b/source/isaaclab/isaaclab/sim/simulation_context.py @@ -583,19 +583,14 @@ def initialize_visualizers(self) -> None: scene_data = self._scene_provider.get_scene_data() - # Check if we have the minimum required data (physics model) - if scene_data.get("model") is not None: - visualizer.initialize(scene_data) - self._visualizers.append(visualizer) - omni.log.info( - f"Initialized visualizer: {type(visualizer).__name__} " - f"(type: {viz_cfg.visualizer_type})" - ) - else: - omni.log.warn( - f"Physics model not available yet for visualizer '{viz_cfg.visualizer_type}'. " - "Visualizer will be initialized later." - ) + # Let each visualizer validate its own requirements + # (e.g., NewtonVisualizer needs Newton model, OVVisualizer needs USD stage) + visualizer.initialize(scene_data) + self._visualizers.append(visualizer) + omni.log.info( + f"Initialized visualizer: {type(visualizer).__name__} " + f"(type: {viz_cfg.visualizer_type})" + ) except Exception as e: omni.log.error( @@ -1055,12 +1050,7 @@ def enable_visualizers(env_cfg, train_mode: bool = True) -> None: ... sim_utils.enable_visualizers(env_cfg) # For training ... sim_utils.enable_visualizers(env_cfg, train_mode=False) # For play/inference """ - from .visualizers import NewtonVisualizerCfg - - if env_cfg.sim.visualizers is None: - # No visualizers in config - use default Newton visualizer - env_cfg.sim.visualizers = NewtonVisualizerCfg(enabled=True, train_mode=train_mode) - else: + if env_cfg.sim.visualizers : # Enable configured visualizer(s) if isinstance(env_cfg.sim.visualizers, list): for viz_cfg in env_cfg.sim.visualizers: diff --git a/source/isaaclab/isaaclab/sim/visualizers/__init__.py b/source/isaaclab/isaaclab/sim/visualizers/__init__.py index 2a7e8ff9ae8..cee4eac6df9 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/__init__.py +++ b/source/isaaclab/isaaclab/sim/visualizers/__init__.py @@ -11,7 +11,7 @@ Supported visualizers: - Newton OpenGL Visualizer: Lightweight OpenGL-based visualizer -- Omniverse Visualizer: High-fidelity Omniverse-based visualizer (coming soon) +- Omniverse Visualizer: High-fidelity Omniverse-based visualizer using Isaac Sim viewport - Rerun Visualizer: Web-based visualizer using the rerun library (coming soon) Visualizer Registry @@ -39,6 +39,7 @@ # Import visualizer implementations from .newton_visualizer import NewtonVisualizer +from .ov_visualizer import OVVisualizer # Global registry for visualizer types (defined after Visualizer import) _VISUALIZER_REGISTRY: dict[str, Any] = {} @@ -48,6 +49,7 @@ "VisualizerCfg", "NewtonVisualizer", "NewtonVisualizerCfg", + "OVVisualizer", "OVVisualizerCfg", "RerunVisualizerCfg", "register_visualizer", @@ -93,5 +95,7 @@ def get_visualizer_class(name: str) -> Type[Visualizer] | None: # Register built-in visualizers # Note: Registration happens here to avoid circular imports _VISUALIZER_REGISTRY["newton"] = NewtonVisualizer +_VISUALIZER_REGISTRY["omniverse"] = OVVisualizer +_VISUALIZER_REGISTRY["ov"] = OVVisualizer # Alias for convenience diff --git a/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py b/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py index 52368afa4fd..fa643dab1db 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py +++ b/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py @@ -288,6 +288,10 @@ def initialize(self, scene_data: dict[str, Any] | None = None) -> None: scene_data: Optional dictionary containing initial scene data. Expected keys: - "model": Newton Model object (required) - "state": Newton State object (optional) + - "metadata": Scene metadata (contains physics_backend) + + Raises: + RuntimeError: If Newton model is not available or if physics backend is incompatible. """ if self._is_initialized: return @@ -299,8 +303,20 @@ def initialize(self, scene_data: dict[str, Any] | None = None) -> None: self._state = scene_data.get("state") metadata = scene_data.get("metadata", {}) + # Validate physics backend compatibility + physics_backend = metadata.get("physics_backend", "unknown") + if physics_backend != "newton" and physics_backend != "unknown": + raise RuntimeError( + f"Newton visualizer requires Newton physics backend, but '{physics_backend}' is running. " + f"Please use a compatible visualizer for {physics_backend} physics (e.g., OVVisualizer)." + ) + + # Validate required data if self._model is None: - raise ValueError("Newton visualizer requires a Newton Model to be provided in scene_data['model']") + raise RuntimeError( + "Newton visualizer requires a Newton Model in scene_data['model']. " + "Make sure Newton physics is initialized before creating the visualizer." + ) # Create the viewer with metadata self._viewer = NewtonViewerGL( @@ -405,6 +421,23 @@ def is_running(self) -> bool: return False return self._viewer.is_running() + + def supports_markers(self) -> bool: + """Check if Newton visualizer supports visualization markers. + + Returns: + False - Newton visualizer currently does not support VisualizationMarkers + (they are USD-based and Newton uses its own rendering). + """ + return False + + def supports_live_plots(self) -> bool: + """Check if Newton visualizer supports live plots. + + Returns: + True - Newton visualizer supports live plots via ImGui integration. + """ + return True def is_training_paused(self) -> bool: """Check if training is paused by the visualizer. diff --git a/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer.py b/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer.py index 095a8b7de49..ceee98e1cd7 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer.py +++ b/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer.py @@ -1,18 +1,310 @@ -# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# Copyright (c) 2022-2025, The Isaac Lab Project Developers. # All rights reserved. # # SPDX-License-Identifier: BSD-3-Clause -"""Omniverse Visualizer implementation.""" +"""Omniverse-based visualizer using Isaac Sim viewport.""" from __future__ import annotations +import omni.log +from typing import Any + +from isaaclab.sim.scene_data_providers import SceneDataProvider + from .ov_visualizer_cfg import OVVisualizerCfg from .visualizer import Visualizer -class OmniverseVisualizer(Visualizer): - """Omniverse Visualizer implementation.""" +class OVVisualizer(Visualizer): + """Omniverse-based visualizer using Isaac Sim viewport. + + This visualizer leverages the existing Isaac Sim application and viewport for visualization. + It provides: + - Automatic rendering of the USD stage in the viewport + - Support for VisualizationMarkers (via USD prims, automatically visible) + - Support for LivePlots (via Isaac Lab UI, automatically displayed) + - Configurable viewport camera positioning + + The visualizer can operate in two modes: + 1. **Attached mode**: Uses an existing Isaac Sim app instance (typical case) + 2. **Standalone mode**: Launches a new Isaac Sim app if none exists (fallback) + + Note: + VisualizationMarkers and LivePlots are managed by the scene and environment, + not directly by this visualizer. This class primarily ensures the viewport + is configured correctly to display them. + """ + def __init__(self, cfg: OVVisualizerCfg): + """Initialize OV visualizer. + + Args: + cfg: Configuration for OV visualizer. + """ super().__init__(cfg) - # stub for now \ No newline at end of file + self.cfg: OVVisualizerCfg = cfg + + # Simulation app instance + self._simulation_app = None + self._app_launched_by_visualizer = False + + # Viewport references + self._viewport_window = None + self._viewport_api = None + + # Internal state + self._is_initialized = False + self._sim_time = 0.0 + self._step_counter = 0 + + def initialize(self, scene_data: dict[str, Any] | None = None) -> None: + """Initialize OV visualizer with scene data. + + This method: + 1. Validates required data (USD stage) + 2. Checks if Isaac Sim app is running, launches if needed + 3. Configures the viewport camera + 4. Prepares for visualization of markers and plots + + Args: + scene_data: Scene data from SceneDataProvider. Contains: + - "usd_stage": The USD stage (required) + - "metadata": Scene metadata (physics backend, num_envs, etc.) + + Raises: + RuntimeError: If USD stage is not available. + + Note: + OV visualizer works with any physics backend (Newton, PhysX, etc.) + as long as a USD stage is available. + """ + if self._is_initialized: + omni.log.warn("[OVVisualizer] Already initialized. Skipping re-initialization.") + return + + # Extract scene data + metadata = {} + usd_stage = None + if scene_data is not None: + usd_stage = scene_data.get("usd_stage") + metadata = scene_data.get("metadata", {}) + + # Validate required data + if usd_stage is None: + raise RuntimeError( + "OV visualizer requires a USD stage in scene_data['usd_stage']. " + "Make sure the simulation context is initialized before creating the visualizer." + ) + + # Check if Isaac Sim app is running + self._ensure_simulation_app() + + # Setup viewport + self._setup_viewport(usd_stage, metadata) + + # Log initialization + physics_backend = metadata.get("physics_backend", "unknown") + num_envs = metadata.get("num_envs", 0) + omni.log.info( + f"[OVVisualizer] Initialized with {num_envs} environments " + f"(physics: {physics_backend})" + ) + + self._is_initialized = True + + def step(self, dt: float, scene_provider: SceneDataProvider | None = None) -> None: + """Update visualizer each step. + + For the OV visualizer, most rendering is handled automatically by Isaac Sim. + This method primarily updates internal timing. + + Args: + dt: Time step in seconds. + scene_provider: Optional scene data provider (not used in minimal implementation). + """ + if not self._is_initialized: + omni.log.warn("[OVVisualizer] Not initialized. Call initialize() first.") + return + + # Update internal state + self._sim_time += dt + self._step_counter += 1 + + # Note: Viewport rendering is handled automatically by Isaac Sim's render loop + # VisualizationMarkers are updated by their respective owners + # LivePlots are updated by ManagerLiveVisualizer + + def close(self) -> None: + """Clean up visualizer resources.""" + if not self._is_initialized: + return + + # Close app if we launched it + if self._app_launched_by_visualizer and self._simulation_app is not None: + omni.log.info("[OVVisualizer] Closing Isaac Sim app launched by visualizer.") + self._simulation_app.close() + self._simulation_app = None + + self._viewport_window = None + self._viewport_api = None + self._is_initialized = False + + def is_running(self) -> bool: + """Check if visualizer is running.""" + if self._simulation_app is None: + return False + return self._simulation_app.is_running() + + def is_training_paused(self) -> bool: + """Check if training is paused. + + Note: OV visualizer does not have a built-in pause mechanism. + Returns False (never pauses training). + """ + return False + + def supports_markers(self) -> bool: + """Check if this visualizer supports visualization markers. + + Returns: + True - OV visualizer supports markers via USD prims. + """ + return True + + def supports_live_plots(self) -> bool: + """Check if this visualizer supports live plots. + + Returns: + True - OV visualizer supports live plots via Isaac Lab UI. + """ + return True + + # ------------------------------------------------------------------ + # Private methods + # ------------------------------------------------------------------ + + def _ensure_simulation_app(self) -> None: + """Ensure Isaac Sim app is running, launch if needed.""" + # Try to get existing SimulationApp instance + try: + from isaacsim import SimulationApp + + # Check if there's an existing app instance + # SimulationApp uses a singleton pattern + if hasattr(SimulationApp, '_instance') and SimulationApp._instance is not None: + self._simulation_app = SimulationApp._instance + omni.log.info("[OVVisualizer] Using existing Isaac Sim app instance.") + return + except ImportError: + omni.log.warn("[OVVisualizer] Could not import SimulationApp. May not be available.") + + # If we get here, no app is running + if not self.cfg.launch_app_if_missing: + omni.log.warn( + "[OVVisualizer] No Isaac Sim app is running and launch_app_if_missing=False. " + "Visualizer may not function correctly." + ) + return + + # Launch a new app + omni.log.info("[OVVisualizer] No Isaac Sim app found. Launching new instance...") + try: + from isaacsim import SimulationApp + + # Launch app with minimal config + launch_config = { + "headless": False, + "experience": self.cfg.app_experience, + } + + self._simulation_app = SimulationApp(launch_config) + self._app_launched_by_visualizer = True + + omni.log.info(f"[OVVisualizer] Launched Isaac Sim app with experience: {self.cfg.app_experience}") + + except Exception as e: + omni.log.error(f"[OVVisualizer] Failed to launch Isaac Sim app: {e}") + self._simulation_app = None + + def _setup_viewport(self, usd_stage, metadata: dict) -> None: + """Setup viewport with camera positioning. + + Args: + usd_stage: USD stage to display. + metadata: Scene metadata. + """ + try: + import omni.kit.viewport.utility as vp_utils + from omni.kit.viewport.utility import get_active_viewport + + # Get the active viewport + if self.cfg.viewport_name: + # Try to get specific viewport by name + self._viewport_window = get_active_viewport() # For now, use active + else: + self._viewport_window = get_active_viewport() + + if self._viewport_window is None: + omni.log.warn("[OVVisualizer] Could not get viewport window.") + return + + # Get viewport API for camera control + self._viewport_api = self._viewport_window.viewport_api + + # Set camera position if specified + if self.cfg.camera_position is not None and self.cfg.camera_target is not None: + self._set_viewport_camera( + self.cfg.camera_position, + self.cfg.camera_target + ) + + omni.log.info("[OVVisualizer] Viewport configured successfully.") + + except ImportError as e: + omni.log.warn(f"[OVVisualizer] Viewport utilities not available: {e}") + except Exception as e: + omni.log.error(f"[OVVisualizer] Error setting up viewport: {e}") + + def _set_viewport_camera( + self, + position: tuple[float, float, float], + target: tuple[float, float, float] + ) -> None: + """Set viewport camera position and target. + + Args: + position: Camera position (x, y, z). + target: Camera target/look-at point (x, y, z). + """ + if self._viewport_api is None: + return + + try: + from pxr import Gf + + # Create camera transformation + eye = Gf.Vec3d(*position) + target_pos = Gf.Vec3d(*target) + up = Gf.Vec3d(0, 0, 1) # Z-up + + # Set camera transform + # Note: The exact API might vary depending on Isaac Sim version + # This is a common pattern, but may need adjustment + transform = Gf.Matrix4d() + transform.SetLookAt(eye, target_pos, up) + + # Try to apply to viewport + # The API for this can vary, so we'll try a few approaches + if hasattr(self._viewport_api, 'set_view'): + self._viewport_api.set_view(eye, target_pos, up) + elif hasattr(self._viewport_window, 'set_camera_position'): + self._viewport_window.set_camera_position(*position, True) + self._viewport_window.set_camera_target(*target, True) + + omni.log.info( + f"[OVVisualizer] Set camera: pos={position}, target={target}" + ) + + except Exception as e: + omni.log.warn(f"[OVVisualizer] Could not set camera transform: {e}") diff --git a/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer_cfg.py b/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer_cfg.py index e67cc47b116..47252a87a46 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer_cfg.py +++ b/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer_cfg.py @@ -1,11 +1,9 @@ -# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# Copyright (c) 2022-2025, The Isaac Lab Project Developers. # All rights reserved. # # SPDX-License-Identifier: BSD-3-Clause -"""Configuration for Omniverse Visualizer.""" - -from typing import Literal +"""Configuration for Omniverse-based visualizer.""" from isaaclab.utils import configclass @@ -14,147 +12,39 @@ @configclass class OVVisualizerCfg(VisualizerCfg): - """Configuration for Omniverse Visualizer. - - The Omniverse Visualizer uses the Omniverse SDK to provide high-fidelity - visualization of the simulation. This is currently implemented through the - Isaac Sim app, but will eventually use the standalone Omniverse SDK module. - - Features: - - High-fidelity rendering with RTX - - Full visual shape support (not just collision shapes) - - USD-based scene representation - - Advanced lighting and materials - - Integration with Omniverse ecosystem + """Configuration for Omniverse-based visualizer. - Note: - The Omniverse Visualizer has higher overhead than the Newton Visualizer - and requires Omniverse/Isaac Sim to be installed. - """ - - # Override defaults for Omniverse visualizer - camera_position: tuple[float, float, float] = (10.0, 10.0, 10.0) - """Initial position of the camera. Default is (10.0, 10.0, 10.0).""" - - window_width: int = 1920 - """Width of the visualizer window in pixels. Default is 1920.""" - - window_height: int = 1080 - """Height of the visualizer window in pixels. Default is 1080.""" - - # Omniverse-specific settings - viewport_name: str = "/OmniverseKit_Persp" - """Name of the viewport to use for visualization. Default is "/OmniverseKit_Persp".""" - - show_origin_axis: bool = True - """Whether to show the origin axis. Default is True.""" - - show_grid: bool = True - """Whether to show the grid. Default is True.""" - - grid_scale: float = 1.0 - """Scale of the grid. Default is 1.0.""" - - enable_scene_lights: bool = True - """Whether to enable scene lights. Default is True.""" - - default_light_intensity: float = 3000.0 - """Default intensity for scene lights. Default is 3000.0.""" - - enable_dome_light: bool = True - """Whether to enable dome (environment) lighting. Default is True.""" - - dome_light_intensity: float = 1000.0 - """Intensity of the dome light. Default is 1000.0.""" - - dome_light_texture: str | None = None - """Path to HDR texture for dome light. Default is None (use default). + This visualizer uses the Isaac Sim application viewport for visualization. + It automatically displays: + - The USD stage (all environment prims) + - VisualizationMarkers (via USD prims) + - LivePlots (via Isaac Lab UI widgets) - If specified, should be a path to an HDR image file for image-based lighting. + The visualizer can operate in two modes: + 1. Attached mode: Uses an existing Isaac Sim app instance + 2. Standalone mode: Launches a new Isaac Sim app if none exists """ - - camera_projection: Literal["perspective", "orthographic"] = "perspective" - """Camera projection type. Default is "perspective".""" - - fov: float = 60.0 - """Field of view for the camera in degrees (for perspective projection). Default is 60.0.""" - - near_plane: float = 0.1 - """Near clipping plane distance. Default is 0.1.""" - - far_plane: float = 10000.0 - """Far clipping plane distance. Default is 10000.0.""" - - enable_ui: bool = True - """Whether to enable the Omniverse UI. Default is True. - When disabled, runs in a more minimal mode which can improve performance. - """ - - ui_window_layout: str | None = None - """Custom UI window layout file. Default is None (use default layout). + visualizer_type: str = "omniverse" - Can be a path to a .json file specifying the UI layout. - """ - - show_selection_outline: bool = True - """Whether to show selection outline on picked objects. Default is True.""" - - show_physics_debug_viz: bool = False - """Whether to show physics debug visualization (contacts, joints). Default is False.""" - - show_bounding_boxes: bool = False - """Whether to show bounding boxes. Default is False.""" - - display_options: int = 3094 - """Display options bitmask. Default is 3094. + # Viewport settings + viewport_name: str = "/OmniverseKit/Viewport" + """Name of the viewport to use. If None, uses the default active viewport.""" - This controls what is visible in the stage. The default value (3094) hides - extra objects that shouldn't appear in visualization. Another common value - is 3286 for the regular editor experience. - """ - - enable_live_sync: bool = False - """Whether to enable live sync with Omniverse. Default is False. + camera_position: tuple[float, float, float] | None = (10.0, 10.0, 10.0) + """Initial camera position for viewport (x, y, z). If None, keeps current camera pose.""" - When enabled, allows other Omniverse clients to connect and view the simulation. - """ - - antialiasing: Literal["Off", "FXAA", "TAA", "DLSS", "DLAA"] = "TAA" - """Anti-aliasing mode. Default is "TAA". + camera_target: tuple[float, float, float] | None = (0.0, 0.0, 0.0) + """Initial camera target/look-at point (x, y, z). If None, keeps current target.""" - - Off: No anti-aliasing - - FXAA: Fast approximate anti-aliasing - - TAA: Temporal anti-aliasing - - DLSS: NVIDIA Deep Learning Super Sampling (requires RTX GPU) - - DLAA: NVIDIA Deep Learning Anti-Aliasing (requires RTX GPU) - """ - - enable_post_processing: bool = True - """Whether to enable post-processing effects. Default is True.""" - - enable_motion_blur: bool = False - """Whether to enable motion blur. Default is False.""" - - enable_depth_of_field: bool = False - """Whether to enable depth of field. Default is False.""" - - background_color: tuple[float, float, float] = (0.0, 0.0, 0.0) - """Background color as RGB values in range [0, 1]. Default is (0.0, 0.0, 0.0) (black).""" - - capture_on_play: bool = False - """Whether to start capturing when play is pressed. Default is False. + # App launch settings (for standalone mode) + launch_app_if_missing: bool = True + """If True and no app is running, launch a new Isaac Sim app instance.""" - Useful for recording the simulation for later playback. - """ - - capture_path: str | None = None - """Path to save captures. Default is None (don't capture). + app_experience: str = "isaac-sim.python.kit" + """Isaac Sim app experience file to use when launching standalone app.""" - When specified, frames will be captured to this path. - """ - - capture_format: Literal["png", "jpg", "exr"] = "png" - """Format for captured images. Default is "png".""" - - + # Environment visibility (for partial visualization - future use) + # NOTE: Partial visualization (REQ-11) is not implemented in this minimal version + # visualize_all_envs: bool = True + # env_indices_to_visualize: list[int] | None = None diff --git a/source/isaaclab/isaaclab/sim/visualizers/visualizer.py b/source/isaaclab/isaaclab/sim/visualizers/visualizer.py index 271da4da78a..bbb684df68c 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/visualizer.py +++ b/source/isaaclab/isaaclab/sim/visualizers/visualizer.py @@ -135,4 +135,29 @@ def is_closed(self) -> bool: True if close() has been called. """ return self._is_closed + + def supports_markers(self) -> bool: + """Check if this visualizer supports visualization markers. + + Visualization markers are geometric shapes (spheres, arrows, frames, etc.) + used for debug visualization. They are typically managed by the scene/environment + but rendered by the visualizer. + + Returns: + True if the visualizer can display VisualizationMarkers, False otherwise. + Default implementation returns False. + """ + return False + + def supports_live_plots(self) -> bool: + """Check if this visualizer supports live plots. + + Live plots display time-series data (observations, rewards, etc.) in real-time + via UI widgets. They are typically managed by manager-based environments. + + Returns: + True if the visualizer can display live plots, False otherwise. + Default implementation returns False. + """ + return False From b67e00e1fb954912746e7477f9bdbdb6e39241ab Mon Sep 17 00:00:00 2001 From: mtrepte Date: Fri, 14 Nov 2025 16:57:08 -0800 Subject: [PATCH 07/24] add rerun viz --- .../isaaclab/isaaclab/sim/simulation_cfg.py | 3 +- .../isaaclab/sim/visualizers/__init__.py | 4 +- .../sim/visualizers/rerun_visualizer.py | 571 +++++++++++++++++- .../sim/visualizers/rerun_visualizer_cfg.py | 202 ++++--- 4 files changed, 677 insertions(+), 103 deletions(-) diff --git a/source/isaaclab/isaaclab/sim/simulation_cfg.py b/source/isaaclab/isaaclab/sim/simulation_cfg.py index a3ff7250f4f..c314d946bd3 100644 --- a/source/isaaclab/isaaclab/sim/simulation_cfg.py +++ b/source/isaaclab/isaaclab/sim/simulation_cfg.py @@ -198,7 +198,8 @@ class SimulationCfg: """Render settings. Default is RenderCfg().""" # visualizers: list[VisualizerCfg] | VisualizerCfg | None = NewtonVisualizerCfg(enabled=True) - visualizers: list[VisualizerCfg] | VisualizerCfg | None = OVVisualizerCfg(enabled=True) + # visualizers: list[VisualizerCfg] | VisualizerCfg | None = OVVisualizerCfg(enabled=True) + visualizers: list[VisualizerCfg] | VisualizerCfg | None = RerunVisualizerCfg(enabled=True) """Visualizer settings. Default is Newton (no visualizer). This field supports multiple visualizer backends for debug visualization and monitoring diff --git a/source/isaaclab/isaaclab/sim/visualizers/__init__.py b/source/isaaclab/isaaclab/sim/visualizers/__init__.py index cee4eac6df9..271897c1030 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/__init__.py +++ b/source/isaaclab/isaaclab/sim/visualizers/__init__.py @@ -40,6 +40,7 @@ # Import visualizer implementations from .newton_visualizer import NewtonVisualizer from .ov_visualizer import OVVisualizer +from .rerun_visualizer import RerunVisualizer # Global registry for visualizer types (defined after Visualizer import) _VISUALIZER_REGISTRY: dict[str, Any] = {} @@ -51,6 +52,7 @@ "NewtonVisualizerCfg", "OVVisualizer", "OVVisualizerCfg", + "RerunVisualizer", "RerunVisualizerCfg", "register_visualizer", "get_visualizer_class", @@ -97,5 +99,5 @@ def get_visualizer_class(name: str) -> Type[Visualizer] | None: _VISUALIZER_REGISTRY["newton"] = NewtonVisualizer _VISUALIZER_REGISTRY["omniverse"] = OVVisualizer _VISUALIZER_REGISTRY["ov"] = OVVisualizer # Alias for convenience - +_VISUALIZER_REGISTRY["rerun"] = RerunVisualizer diff --git a/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer.py b/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer.py index 7758a938d6e..6c356c4dd8c 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer.py +++ b/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer.py @@ -1,18 +1,579 @@ -# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# Copyright (c) 2022-2025, The Isaac Lab Project Developers. # All rights reserved. # # SPDX-License-Identifier: BSD-3-Clause -"""Omniverse Visualizer implementation.""" +"""Rerun-based visualizer using rerun-sdk.""" from __future__ import annotations -from .ov_visualizer_cfg import RerunVisualizerCfg +import numpy as np +import omni.log +import torch +from typing import Any + +from isaaclab.sim.scene_data_providers import SceneDataProvider + +from .rerun_visualizer_cfg import RerunVisualizerCfg from .visualizer import Visualizer +# Try to import rerun and Newton's ViewerRerun +try: + import rerun as rr + import rerun.blueprint as rrb + from newton.viewer import ViewerRerun + + _RERUN_AVAILABLE = True +except ImportError: + rr = None + rrb = None + ViewerRerun = None + _RERUN_AVAILABLE = False + + +class NewtonViewerRerun(ViewerRerun if _RERUN_AVAILABLE else object): + """Isaac Lab wrapper around Newton's ViewerRerun. + + This wrapper adds Isaac Lab-specific features on top of Newton's base ViewerRerun: + + - Integration with Isaac Lab's VisualizationMarkers system + - Integration with Isaac Lab's LivePlots system + - Environment metadata display + - Custom Rerun blueprint for Isaac Lab workflow + - Partial environment visualization support + + The wrapper uses composition to extend Newton's ViewerRerun without modifying + the base Newton library, similar to how NewtonViewerGL wraps ViewerGL. + + Note: + This class requires Newton physics backend and rerun-sdk to be installed. + """ + + def __init__( + self, + # Newton ViewerRerun parameters + server: bool = True, + address: str = "127.0.0.1:9876", + launch_viewer: bool = True, + app_id: str | None = None, + keep_historical_data: bool = False, + keep_scalar_history: bool = True, + record_to_rrd: str | None = None, + # Isaac Lab-specific parameters + train_mode: bool = True, + metadata: dict | None = None, + visualize_markers: bool = True, + visualize_plots: bool = True, + env_indices: list[int] | None = None, + ): + """Initialize Isaac Lab Rerun viewer wrapper. + + Args: + server: If True, start rerun in server mode (gRPC). + address: Address and port for rerun server mode. + launch_viewer: If True, launch a local rerun viewer client. + app_id: Application ID for rerun (defaults to 'newton-viewer'). + keep_historical_data: If True, keep historical data in the timeline. + keep_scalar_history: If True, keep historical scalar data. + record_to_rrd: Path to record viewer to .rrd file. + train_mode: Whether in training mode (affects behavior/UI). + metadata: Scene metadata (num_envs, physics backend, etc.). + visualize_markers: Whether to actively log VisualizationMarkers. + visualize_plots: Whether to actively log LivePlot data. + env_indices: Which environments to visualize (None = all). + """ + if not _RERUN_AVAILABLE: + raise ImportError( + "Rerun visualizer requires rerun-sdk and Newton to be installed. " + "Install with: pip install rerun-sdk" + ) + + # Call parent constructor with only Newton parameters + super().__init__( + server=server, + address=address, + launch_viewer=launch_viewer, + app_id=app_id, + # keep_historical_data=keep_historical_data, + # keep_scalar_history=keep_scalar_history, + # record_to_rrd=record_to_rrd, + ) + + # Isaac Lab specific state + self._metadata = metadata or {} + self._train_mode = train_mode + self._visualize_markers = visualize_markers + self._visualize_plots = visualize_plots + self._env_indices = env_indices + + # Storage for registered markers and plots + self._registered_markers = [] + self._registered_plots = {} + + # Log metadata on initialization + self._log_metadata() + + def _log_metadata(self) -> None: + """Log scene metadata to Rerun as text.""" + metadata_text = "# Isaac Lab Scene Metadata\n\n" + + # Physics info + physics_backend = self._metadata.get("physics_backend", "unknown") + metadata_text += f"**Physics Backend:** {physics_backend}\n" + + # Environment info + num_envs = self._metadata.get("num_envs", 0) + metadata_text += f"**Total Environments:** {num_envs}\n" + + if self._env_indices is not None: + metadata_text += f"**Visualized Environments:** {len(self._env_indices)} (indices: {self._env_indices[:5]}...)\n" + else: + metadata_text += f"**Visualized Environments:** All ({num_envs})\n" + + # Mode info + mode = "Training" if self._train_mode else "Inference/Play" + metadata_text += f"**Mode:** {mode}\n" + + # Visualization features + metadata_text += f"**Markers Enabled:** {self._visualize_markers}\n" + metadata_text += f"**Plots Enabled:** {self._visualize_plots}\n" + + # Additional metadata + for key, value in self._metadata.items(): + if key not in ["physics_backend", "num_envs"]: + metadata_text += f"**{key}:** {value}\n" + + # Log to Rerun + rr.log("metadata", rr.TextDocument(metadata_text, media_type=rr.MediaType.MARKDOWN)) + + def register_markers(self, markers: Any) -> None: + """Register VisualizationMarkers for active logging. + + Args: + markers: VisualizationMarkers instance to log each frame. + """ + if self._visualize_markers: + self._registered_markers.append(markers) + omni.log.info(f"[RerunVisualizer] Registered markers: {markers}") + + def register_plots(self, plots: dict[str, Any]) -> None: + """Register LivePlot instances for active logging. + + Args: + plots: Dictionary mapping plot names to LivePlot instances. + """ + if self._visualize_plots: + self._registered_plots.update(plots) + omni.log.info(f"[RerunVisualizer] Registered {len(plots)} plot(s)") + + def log_markers(self) -> None: + """Actively log all registered VisualizationMarkers to Rerun. + + This method converts Isaac Lab's USD-based markers to Rerun entities. + + Supported marker types: + - Arrows: Logged as line segments via rr.LineStrips3D + - Frames: Logged as XYZ axes via rr.LineStrips3D (3 lines per frame) + - Spheres: Logged as points via rr.Points3D with radii + + Implementation Strategy: + We convert USD-based visualization markers to Rerun primitives. + Since markers are scene-managed and updated by their owners, + we need to extract their current state each frame and log it. + + TODO: Future enhancements + - Support more marker types (cylinders, cones, boxes) + - Optimize batch logging for large marker counts + - Add color/material support for better visual distinction + """ + if not self._visualize_markers or len(self._registered_markers) == 0: + return + + try: + for marker_idx, markers in enumerate(self._registered_markers): + # Extract marker data + # Note: This is a simplified implementation that assumes markers + # expose their data through specific methods/properties. + # Actual implementation depends on VisualizationMarkers API. + + # For now, we'll use Newton's built-in logging methods + # which VisualizationMarkers should be compatible with + + # TODO: Implement proper marker extraction and conversion + # marker_data = markers.get_marker_data() + # self._log_marker_data(marker_data, f"markers/{marker_idx}") + + pass # Stub for now + + except Exception as e: + omni.log.warn(f"[RerunVisualizer] Failed to log markers: {e}") + + def log_plot_data(self) -> None: + """Actively log all registered LivePlot data to Rerun as time series. + + This method extracts scalar data from LivePlot objects and logs them + as Rerun Scalars, enabling visualization alongside the 3D scene. + + Implementation Strategy: + LivePlots in Isaac Lab are typically omni.ui-based widgets that + display time-series data. For Rerun, we need to extract the raw + scalar values and log them using rr.Scalar(). + + TODO: Full implementation + - Extract data from LiveLinePlot objects + - Handle multiple series per plot + - Maintain proper timeline synchronization + - Support different plot types (line, bar, etc.) + """ + if not self._visualize_plots or len(self._registered_plots) == 0: + return + + try: + for plot_name, plot_obj in self._registered_plots.items(): + # TODO: Extract data from plot object + # For now, this is a stub + # data = plot_obj.get_latest_data() + # rr.log(f"plots/{plot_name}", rr.Scalar(data)) + + pass # Stub for now + + except Exception as e: + omni.log.warn(f"[RerunVisualizer] Failed to log plot data: {e}") + + def _log_marker_data(self, marker_data: dict, entity_path: str) -> None: + """Helper to log specific marker data to Rerun. + + Args: + marker_data: Dictionary containing marker positions, types, colors, etc. + entity_path: Rerun entity path for logging. + """ + marker_type = marker_data.get("type", "unknown") + + if marker_type == "arrow": + # Log arrows as line segments + starts = marker_data.get("positions") # Start points + directions = marker_data.get("directions") # Direction vectors + + if starts is not None and directions is not None: + ends = starts + directions + self.log_lines( + entity_path, + starts=starts, + ends=ends, + colors=marker_data.get("colors"), + width=marker_data.get("width", 0.01), + ) + + elif marker_type == "frame": + # Log coordinate frames as 3 lines (XYZ axes) + positions = marker_data.get("positions") + orientations = marker_data.get("orientations") + scale = marker_data.get("scale", 0.1) + + if positions is not None and orientations is not None: + # TODO: Convert quaternions to XYZ axis lines + # For each frame, create 3 lines (red=X, green=Y, blue=Z) + pass + + elif marker_type == "sphere": + # Log spheres as points with radii + positions = marker_data.get("positions") + radii = marker_data.get("radii", 0.05) + colors = marker_data.get("colors") + + if positions is not None: + self.log_points( + entity_path, + points=positions, + radii=radii, + colors=colors, + ) + class RerunVisualizer(Visualizer): - """Omniverse Visualizer implementation.""" + """Rerun-based visualizer for Isaac Lab using rerun-sdk. + + This visualizer provides web-based visualization with advanced features: + + - **Time Scrubbing**: Rewind and replay simulation timeline + - **Data Inspection**: Inspect transforms, meshes, and data in detail + - **Recording**: Save to .rrd files for offline analysis + - **Active Logging**: Explicitly logs markers and plots (unlike passive OV visualizer) + + The Rerun visualizer wraps Newton's ViewerRerun and requires the Newton physics + backend. It uses active logging, meaning all visualization data (markers, plots) + must be explicitly logged each frame, unlike the OV visualizer where USD-based + markers automatically appear. + + Requirements: + - Newton physics backend (scene_data must contain Newton Model and State) + - rerun-sdk package: ``pip install rerun-sdk`` + + Future Support: + - PhysX backend support (planned for future release) + - Additional marker types (cylinders, cones, boxes) + - Full LivePlot integration (currently stub) + + Example: + + .. code-block:: python + + from isaaclab.sim import SimulationCfg + from isaaclab.sim.visualizers import RerunVisualizerCfg + + sim_cfg = SimulationCfg( + dt=0.01, + visualizers=RerunVisualizerCfg( + enabled=True, + launch_viewer=True, + keep_historical_data=False, # Constant memory + ), + ) + """ + def __init__(self, cfg: RerunVisualizerCfg): + """Initialize Rerun visualizer. + + Args: + cfg: Configuration for Rerun visualizer. + + Raises: + ImportError: If rerun-sdk or Newton is not installed. + """ super().__init__(cfg) - # stub for now \ No newline at end of file + self.cfg: RerunVisualizerCfg = cfg + + # Check dependencies + if not _RERUN_AVAILABLE: + raise ImportError( + "Rerun visualizer requires rerun-sdk and Newton to be installed.\n" + "Install with: pip install rerun-sdk\n" + "Make sure Newton physics is also available in your environment." + ) + + # Will be initialized in initialize() + self._viewer: NewtonViewerRerun | None = None + self._model = None + self._state = None + self._is_initialized = False + self._sim_time = 0.0 + + def initialize(self, scene_data: dict[str, Any] | None = None) -> None: + """Initialize Rerun visualizer with scene data. + + This method: + 1. Validates required data (Newton Model and State) + 2. Checks physics backend compatibility + 3. Creates NewtonViewerRerun instance with Isaac Lab extensions + 4. Sets up the model for visualization + + Args: + scene_data: Scene data from SceneDataProvider. Must contain: + - "model": Newton Model (required) + - "state": Newton State (required) + - "metadata": Scene metadata (physics backend, num_envs, etc.) + + Raises: + RuntimeError: If Newton Model/State is not available or physics backend is incompatible. + """ + if self._is_initialized: + omni.log.warn("[RerunVisualizer] Already initialized. Skipping re-initialization.") + return + + # Extract scene data + metadata = {} + if scene_data is not None: + self._model = scene_data.get("model") + self._state = scene_data.get("state") + metadata = scene_data.get("metadata", {}) + + # Validate physics backend + physics_backend = metadata.get("physics_backend", "unknown") + if physics_backend != "newton" and physics_backend != "unknown": + raise RuntimeError( + f"Rerun visualizer currently requires Newton physics backend, " + f"but '{physics_backend}' is running. " + f"Please use a compatible visualizer for {physics_backend} physics " + f"(e.g., OVVisualizer).\n\n" + f"Future versions will support multiple physics backends." + ) + + # Validate required Newton data + if self._model is None: + raise RuntimeError( + "Rerun visualizer requires a Newton Model in scene_data['model']. " + "Make sure Newton physics is initialized before creating the visualizer." + ) + + if self._state is None: + omni.log.warn( + "[RerunVisualizer] No Newton State provided in scene_data['state']. " + "Visualization may not work correctly." + ) + + # Create Newton ViewerRerun wrapper + try: + self._viewer = NewtonViewerRerun( + server=self.cfg.server_mode, + address=self.cfg.server_address, + launch_viewer=self.cfg.launch_viewer, + app_id=self.cfg.app_id, + keep_historical_data=self.cfg.keep_historical_data, + keep_scalar_history=self.cfg.keep_scalar_history, + record_to_rrd=self.cfg.record_to_rrd, + train_mode=self.cfg.train_mode, + metadata=metadata, + visualize_markers=self.cfg.visualize_markers, + visualize_plots=self.cfg.visualize_plots, + env_indices=self.cfg.env_indices, + ) + + # Set the model + self._viewer.set_model(self._model) + + # Log initialization + num_envs = metadata.get("num_envs", 0) + viz_envs = len(self.cfg.env_indices) if self.cfg.env_indices else num_envs + omni.log.info( + f"[RerunVisualizer] Initialized with {viz_envs}/{num_envs} environments " + f"(physics: {physics_backend})" + ) + + self._is_initialized = True + + except Exception as e: + omni.log.error(f"[RerunVisualizer] Failed to initialize viewer: {e}") + raise + + def step(self, dt: float, scene_provider: SceneDataProvider | None = None) -> None: + """Update visualizer each step. + + This method: + 1. Updates state from scene provider (if available) + 2. Logs current state to Rerun (transforms, meshes) + 3. Actively logs markers (if enabled) + 4. Actively logs plot data (if enabled) + + Implementation Note: + Partial visualization (env_indices) is handled internally by filtering + which instance transforms are logged. We log all meshes once (they're + shared assets), but only log transforms for selected environments. + + Alternative implementations: + - Option A: Filter at the Newton state level (more invasive) + - Option B: Filter during logging (current - most flexible) + - Option C: Filter at the scene provider level (future consideration) + + Args: + dt: Time step in seconds. + scene_provider: Optional scene data provider for updated state. + """ + if not self._is_initialized or self._viewer is None: + omni.log.warn("[RerunVisualizer] Not initialized. Call initialize() first.") + return + + # Update state from scene provider if available + if scene_provider is not None: + self._state = scene_provider.get_state() + + # Begin frame + self._viewer.begin_frame(self._sim_time) + + # Log state (transforms) - Newton's ViewerRerun handles this + if self._state is not None: + # Handle partial visualization if env_indices is set + if self.cfg.env_indices is not None: + # TODO: Filter state to only visualized environments + # For now, log all state (Newton's ViewerRerun will handle it) + self._viewer.log_state(self._state) + else: + self._viewer.log_state(self._state) + + # Actively log markers (if enabled) + if self.cfg.visualize_markers: + self._viewer.log_markers() + + # Actively log plot data (if enabled) + if self.cfg.visualize_plots: + self._viewer.log_plot_data() + + # End frame + self._viewer.end_frame() + + # Update internal time + self._sim_time += dt + + def close(self) -> None: + """Clean up Rerun visualizer resources. + + This closes the Rerun viewer, disconnects from the server, and + finalizes any recording files. + """ + if not self._is_initialized or self._viewer is None: + return + + try: + self._viewer.close() + omni.log.info("[RerunVisualizer] Closed successfully.") + except Exception as e: + omni.log.warn(f"[RerunVisualizer] Error during close: {e}") + + self._viewer = None + self._is_initialized = False + + def is_running(self) -> bool: + """Check if visualizer is running. + + Returns: + True if viewer is initialized and running, False otherwise. + """ + if self._viewer is None: + return False + return self._viewer.is_running() + + def is_training_paused(self) -> bool: + """Check if training is paused. + + Note: + Rerun visualizer uses Rerun's built-in timeline controls for playback. + It does not provide a training pause mechanism like NewtonVisualizer. + + Returns: + False - Rerun does not support training pause. + """ + return False + + def supports_markers(self) -> bool: + """Check if this visualizer supports visualization markers. + + Returns: + True - Rerun supports markers via active logging. + """ + return True + + def supports_live_plots(self) -> bool: + """Check if this visualizer supports live plots. + + Returns: + True - Rerun supports plots via active logging (currently stub). + """ + return True + + def register_markers(self, markers: Any) -> None: + """Register VisualizationMarkers for active logging. + + Args: + markers: VisualizationMarkers instance to visualize. + """ + if self._viewer: + self._viewer.register_markers(markers) + + def register_plots(self, plots: dict[str, Any]) -> None: + """Register LivePlot instances for active logging. + + Args: + plots: Dictionary mapping plot names to LivePlot instances. + """ + if self._viewer: + self._viewer.register_plots(plots) + diff --git a/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer_cfg.py b/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer_cfg.py index 487bc6e69eb..d366f1a5bfb 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer_cfg.py +++ b/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer_cfg.py @@ -1,11 +1,11 @@ -# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# Copyright (c) 2022-2025, The Isaac Lab Project Developers. # All rights reserved. # # SPDX-License-Identifier: BSD-3-Clause -"""Configuration for Rerun Visualizer.""" +"""Configuration for the Rerun visualizer.""" -from typing import Literal +from __future__ import annotations from isaaclab.utils import configclass @@ -14,146 +14,156 @@ @configclass class RerunVisualizerCfg(VisualizerCfg): - """Configuration for Rerun Visualizer. + """Configuration for the Rerun visualizer using rerun-sdk. - The Rerun Visualizer integrates with the rerun visualization library, enabling - real-time or offline visualization with advanced features like time scrubbing - and data inspection through a web-based interface. + The Rerun visualizer provides web-based visualization with advanced features: - Features: - - Web-based visualization interface - Time scrubbing and playback controls - - 3D scene navigation - - Data inspection and filtering - - Recording and export capabilities - - Remote viewing support + - 3D scene navigation and inspection + - Data filtering and analysis + - Recording to .rrd files for offline replay + - Built-in timeline and data inspection tools + + This visualizer requires the Newton physics backend and the rerun-sdk package: + + .. code-block:: bash + + pip install rerun-sdk Note: - Requires the rerun-sdk package to be installed: pip install rerun-sdk - """ - - # Override defaults for Rerun visualizer - camera_position: tuple[float, float, float] = (10.0, 10.0, 10.0) - """Initial position of the camera. Default is (10.0, 10.0, 10.0).""" - - # Rerun-specific settings + The Rerun visualizer wraps Newton's ViewerRerun, which requires a Newton Model + and State. It will not work with other physics backends (e.g., PhysX) until + future support is added. + + Example: + + .. code-block:: python + + from isaaclab.sim.visualizers import RerunVisualizerCfg + + visualizer_cfg = RerunVisualizerCfg( + enabled=True, + server_mode=True, + launch_viewer=True, + keep_historical_data=False, # Constant memory for training + record_to_rrd="recording.rrd", # Save to file + ) + """ + + visualizer_type: str = "rerun" + """Type identifier for the Rerun visualizer. Defaults to "rerun".""" + + # Connection settings server_mode: bool = True - """Whether to run in server mode. Default is True. + """Whether to run Rerun in server mode (gRPC). Defaults to True. - In server mode, Rerun starts a server that viewers can connect to. - When False, data is logged to a file or sent to an external viewer. + If True, Rerun will start a gRPC server that the web viewer connects to. + If False, data is logged directly (useful for recording to file only). """ server_address: str = "127.0.0.1:9876" - """Server address for Rerun. Default is "127.0.0.1:9876". + """Server address and port for gRPC mode. Defaults to "127.0.0.1:9876". - Format: "host:port". Only used when server_mode is True. + Only used if server_mode=True. The web viewer will connect to this address. """ launch_viewer: bool = True - """Whether to automatically launch the web viewer. Default is True. + """Whether to auto-launch the web viewer. Defaults to True. - When True, the Rerun web viewer will be automatically opened in a browser. + If True, a web browser will open showing the Rerun viewer interface. + The viewer provides 3D visualization, timeline controls, and data inspection. """ app_id: str = "isaaclab-simulation" - """Application identifier for Rerun. Default is "isaaclab-simulation". + """Application identifier for Rerun. Defaults to "isaaclab-simulation". - This is used to identify the application in the Rerun viewer and for - organizing recordings. + This is displayed in the Rerun viewer title and used to distinguish + multiple Rerun sessions. """ - recording_path: str | None = None - """Path to save recordings. Default is None (don't save). + # Data management + keep_historical_data: bool = False + """Whether to keep historical transform data in viewer timeline. Defaults to False. - When specified, the Rerun data will be saved to this path for later replay. - Supported formats: .rrd (Rerun recording format) - """ - - spawn_mode: Literal["connect", "spawn", "save"] = "spawn" - """How to handle the Rerun viewer. Default is "spawn". + - If False: Only current frame is kept, memory usage is constant (good for training) + - If True: Full timeline is kept, enables time scrubbing (good for debugging) - - "connect": Connect to an existing Rerun viewer - - "spawn": Spawn a new Rerun viewer process - - "save": Save to a file without opening a viewer + For long training runs with many environments, False is recommended to avoid + memory issues. For analysis and debugging, True allows rewinding the simulation. """ - max_queue_size: int = 100 - """Maximum number of messages to queue. Default is 100. + keep_scalar_history: bool = True + """Whether to keep historical scalar/plot data in viewer. Defaults to True. - Controls memory usage for buffering visualization data. + Scalar data (plots, metrics) is typically small, so keeping history is + reasonable even for long runs. This enables viewing plot trends over time. """ - flush_timeout: float = 2.0 - """Timeout for flushing data to Rerun in seconds. Default is 2.0.""" - - log_transforms: bool = True - """Whether to log rigid body transforms. Default is True.""" - - log_meshes: bool = True - """Whether to log mesh data. Default is True. + # Recording + record_to_rrd: str | None = None + """Path to save recording as .rrd file. Defaults to None (no recording). - When enabled, collision and visual meshes will be logged to Rerun. - """ - - log_cameras: bool = True - """Whether to log camera data. Default is True.""" - - log_point_clouds: bool = False - """Whether to log point cloud data. Default is False.""" - - log_images: bool = False - """Whether to log images from cameras. Default is False. + If specified (e.g., "my_recording.rrd"), all logged data will be saved to + this file for offline replay and analysis. The file can be opened later with: - Note: Logging images can significantly increase data size and bandwidth. - """ - - log_tensors: bool = False - """Whether to log tensor data (observations, actions, etc.). Default is False. + .. code-block:: bash - When enabled, can log observation buffers, action buffers, and other tensors. - """ - - time_mode: Literal["sim_time", "wall_time", "step_count"] = "sim_time" - """Time mode for logging. Default is "sim_time". + rerun my_recording.rrd - - "sim_time": Use simulation time as the timeline - - "wall_time": Use wall clock time - - "step_count": Use step count as the timeline + Example paths: + - "recording.rrd" - saves to current directory + - "/tmp/recordings/run_{timestamp}.rrd" - absolute path with timestamp + - None - no recording saved """ - entity_path_prefix: str = "/world" - """Prefix for entity paths in Rerun. Default is "/world". + # Visualization options + log_transforms: bool = True + """Whether to log rigid body transforms. Defaults to True. - All logged entities will be under this prefix in the Rerun hierarchy. + Transform logging shows the position and orientation of all rigid bodies + in the scene. This is the core visualization data. """ - log_static_once: bool = True - """Whether to log static scene data only once. Default is True. + log_meshes: bool = True + """Whether to log mesh geometry. Defaults to True. - When True, static meshes and other unchanging data are logged only at the - start, reducing data size and bandwidth. + Mesh logging shows the 3D shapes of objects. If False, only transforms + (positions/orientations) are shown as coordinate frames. """ - up_axis: Literal["+x", "-x", "+y", "-y", "+z", "-z"] = "+z" - """The up axis for the 3D space. Default is "+z". + visualize_markers: bool = True + """Whether to actively log VisualizationMarkers to Rerun. Defaults to True. - This should match your simulation's coordinate system. + If True, markers created via VisualizationMarkers (arrows, frames, spheres, etc.) + will be converted to Rerun entities and logged each frame. This requires active + logging (unlike OV visualizer where markers auto-appear in the viewport). + + Supported marker types: + - Arrows (via log_lines) + - Coordinate frames (via log_lines for XYZ axes) + - Spheres (via log_points) """ - mesh_quality: Literal["low", "medium", "high"] = "medium" - """Quality level for mesh data. Default is "medium". + visualize_plots: bool = True + """Whether to actively log LivePlot data to Rerun. Defaults to True. + + If True, scalar data from LivePlots will be logged as time series in Rerun. + This allows viewing training metrics, rewards, and other scalars alongside + the 3D visualization. - Higher quality preserves more detail but increases data size. + Note: Currently a stub - full implementation coming soon. """ - enable_compression: bool = True - """Whether to enable data compression. Default is True. + # Performance and filtering + max_instances_per_env: int | None = None + """Maximum number of instances to visualize per environment. Defaults to None (all). - Compression reduces bandwidth and storage requirements but adds CPU overhead. + For scenes with many instances per environment, this limits how many are + visualized to improve performance. None means visualize all instances. """ - verbose: bool = False - """Whether to enable verbose logging. Default is False.""" - + # Future: PhysX backend support + # When PhysX support is added, these fields will be used: + # physics_backend: Literal["newton", "physx"] | None = None + # """Physics backend to use. Auto-detected if None.""" From 30116c02333e97759ee63c1a9b16e99fc25fa420 Mon Sep 17 00:00:00 2001 From: mtrepte Date: Fri, 14 Nov 2025 17:40:28 -0800 Subject: [PATCH 08/24] clean --- .../isaaclab/isaaclab/sim/simulation_cfg.py | 3 +- .../sim/visualizers/newton_visualizer.py | 24 +-- .../sim/visualizers/newton_visualizer_cfg.py | 95 +++------ .../isaaclab/sim/visualizers/ov_visualizer.py | 184 +++++------------- .../sim/visualizers/ov_visualizer_cfg.py | 40 ++-- .../sim/visualizers/rerun_visualizer.py | 151 +++----------- .../sim/visualizers/rerun_visualizer_cfg.py | 147 ++------------ .../isaaclab/sim/visualizers/visualizer.py | 111 ++--------- .../sim/visualizers/visualizer_cfg.py | 89 ++------- source/isaaclab/setup.py | 4 +- 10 files changed, 161 insertions(+), 687 deletions(-) diff --git a/source/isaaclab/isaaclab/sim/simulation_cfg.py b/source/isaaclab/isaaclab/sim/simulation_cfg.py index c314d946bd3..dc445985978 100644 --- a/source/isaaclab/isaaclab/sim/simulation_cfg.py +++ b/source/isaaclab/isaaclab/sim/simulation_cfg.py @@ -199,7 +199,8 @@ class SimulationCfg: # visualizers: list[VisualizerCfg] | VisualizerCfg | None = NewtonVisualizerCfg(enabled=True) # visualizers: list[VisualizerCfg] | VisualizerCfg | None = OVVisualizerCfg(enabled=True) - visualizers: list[VisualizerCfg] | VisualizerCfg | None = RerunVisualizerCfg(enabled=True) + # visualizers: list[VisualizerCfg] | VisualizerCfg | None = RerunVisualizerCfg(enabled=True) + visualizers: list[VisualizerCfg] | VisualizerCfg | None = [NewtonVisualizerCfg(enabled=True), RerunVisualizerCfg(enabled=True)] """Visualizer settings. Default is Newton (no visualizer). This field supports multiple visualizer backends for debug visualization and monitoring diff --git a/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py b/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py index fa643dab1db..6314e6744f3 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py +++ b/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py @@ -29,12 +29,11 @@ class NewtonViewerGL(ViewerGL): The training pause can be toggled from the UI via a button and optionally via the 'T' key. """ - def __init__(self, *args, train_mode: bool = True, metadata: dict | None = None, **kwargs): + def __init__(self, *args, metadata: dict | None = None, **kwargs): super().__init__(*args, **kwargs) self._paused_training: bool = False self._paused_rendering: bool = False self._fallback_draw_controls: bool = False - self._is_train_mode: bool = train_mode self._visualizer_update_frequency: int = 1 self._metadata = metadata or {} @@ -70,23 +69,15 @@ def get_visualizer_update_frequency(self) -> int: # UI callback rendered inside the "Example Options" panel of the left sidebar def _render_training_controls(self, imgui): imgui.separator() - - # Use simple flag to adjust labels - if self._is_train_mode: - imgui.text("IsaacLab Training Controls") - pause_label = "Resume Training" if self._paused_training else "Pause Training" - else: - imgui.text("IsaacLab Playback Controls") - pause_label = "Resume Playing" if self._paused_training else "Pause Playing" - + imgui.text("Isaac Lab Training Controls") + + pause_label = "Resume Training" if self._paused_training else "Pause Training" if imgui.button(pause_label): self._paused_training = not self._paused_training - # Only show rendering controls when in training mode - if self._is_train_mode: - rendering_label = "Resume Rendering" if self._paused_rendering else "Pause Rendering" - if imgui.button(rendering_label): - self._paused_rendering = not self._paused_rendering + rendering_label = "Resume Rendering" if self._paused_rendering else "Pause Rendering" + if imgui.button(rendering_label): + self._paused_rendering = not self._paused_rendering imgui.text("Visualizer Update Frequency") @@ -322,7 +313,6 @@ def initialize(self, scene_data: dict[str, Any] | None = None) -> None: self._viewer = NewtonViewerGL( width=self.cfg.window_width, height=self.cfg.window_height, - train_mode=self.cfg.train_mode, metadata=metadata, ) diff --git a/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer_cfg.py b/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer_cfg.py index dadf5ad88ef..ccbd183ac80 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer_cfg.py +++ b/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer_cfg.py @@ -14,123 +14,82 @@ @configclass class NewtonVisualizerCfg(VisualizerCfg): - """Configuration for Newton OpenGL Visualizer. + """Configuration for Newton OpenGL visualizer. - The Newton OpenGL Visualizer is a lightweight, fast visualizer built on OpenGL. - It is designed for interactive real-time visualization of simulations with minimal - performance overhead. It requires pyglet (version >= 2.1.6) and imgui_bundle - (version >= 1.92.0) to be installed. + Lightweight OpenGL-based visualizer with real-time 3D rendering, interactive + camera controls, and debug visualization (contacts, joints, springs, COM). - Features: - - Real-time 3D visualization - - Interactive camera controls - - Debug visualization (contacts, joints, springs, COM) - - Training controls (pause training, pause rendering, update frequency) - - Lightweight and fast - - Note: - The Newton Visualizer currently only supports visualization of collision shapes, - not visual shapes. + Requires: pyglet >= 2.1.6, imgui_bundle >= 1.92.0 """ - # Visualizer type identifier visualizer_type: str = "newton" - """Type identifier for Newton visualizer. Used by the factory pattern.""" - - # Override defaults for Newton visualizer - camera_position: tuple[float, float, float] = (10.0, 0.0, 3.0) - """Initial position of the camera. Default is (10.0, 0.0, 3.0).""" + """Type identifier for Newton visualizer.""" window_width: int = 1920 - """Width of the visualizer window in pixels. Default is 1920.""" + """Window width in pixels.""" window_height: int = 1080 - """Height of the visualizer window in pixels. Default is 1080.""" + """Window height in pixels.""" # Newton-specific settings fps: int = 60 - """Target frames per second for the visualizer. Default is 60.""" + """Target FPS.""" show_joints: bool = True - """Whether to show joint visualizations. Default is True.""" + """Show joint visualizations.""" show_contacts: bool = False - """Whether to show contact visualizations. Default is False.""" + """Show contact visualizations.""" show_springs: bool = False - """Whether to show spring visualizations. Default is False.""" + """Show spring visualizations.""" show_com: bool = False - """Whether to show center of mass visualizations. Default is False.""" + """Show center of mass visualizations.""" show_ui: bool = True - """Whether to show the UI sidebar. Default is True. - - The UI can be toggled with the 'H' key during runtime. - """ + """Show UI sidebar (toggle with 'H' key).""" enable_shadows: bool = True - """Whether to enable shadow rendering. Default is True.""" + """Enable shadow rendering.""" enable_sky: bool = True - """Whether to enable sky rendering. Default is True.""" + """Enable sky rendering.""" enable_wireframe: bool = False - """Whether to enable wireframe rendering mode. Default is False.""" + """Enable wireframe rendering mode.""" up_axis: Literal["X", "Y", "Z"] = "Z" - """The up axis for the visualizer. Default is "Z". - - This should typically match the up axis of your simulation environment. - """ + """Up axis for visualizer (should match simulation).""" fov: float = 60.0 - """Field of view for the camera in degrees. Default is 60.0.""" + """Camera field of view in degrees.""" near_plane: float = 0.1 - """Near clipping plane distance for the camera. Default is 0.1.""" + """Camera near clipping plane distance.""" far_plane: float = 1000.0 - """Far clipping plane distance for the camera. Default is 1000.0.""" + """Camera far clipping plane distance.""" background_color: tuple[float, float, float] = (0.53, 0.81, 0.92) - """Background color (sky color) as RGB values in range [0, 1]. - Default is (0.53, 0.81, 0.92) (light blue).""" + """Background/sky color RGB [0,1] (light blue).""" ground_color: tuple[float, float, float] = (0.18, 0.20, 0.25) - """Ground color as RGB values in range [0, 1]. - Default is (0.18, 0.20, 0.25) (dark gray).""" + """Ground color RGB [0,1] (dark gray).""" light_color: tuple[float, float, float] = (1.0, 1.0, 1.0) - """Light color as RGB values in range [0, 1]. Default is (1.0, 1.0, 1.0) (white).""" + """Light color RGB [0,1] (white).""" enable_pause_training: bool = True - """Whether to enable the pause training button in the UI. Default is True. - - When enabled, users can pause the simulation/training while keeping the - visualizer running, which is useful for debugging. - """ + """Enable pause training button in UI.""" enable_pause_rendering: bool = True - """Whether to enable the pause rendering button in the UI. Default is True. - - When enabled, users can pause rendering while keeping simulation/training - running, which can improve training performance. - """ + """Enable pause rendering button in UI.""" show_training_controls: bool = True - """Whether to show IsaacLab-specific training controls in the UI. Default is True. - - This includes controls for pausing training, pausing rendering, and adjusting - the visualizer update frequency. - """ + """Show Isaac Lab training controls in UI.""" render_mode: Literal["rgb", "depth", "collision"] = "rgb" - """Rendering mode for the visualizer. Default is "rgb". - - - "rgb": Standard RGB rendering - - "depth": Depth visualization - - "collision": Show collision shapes only - """ + """Rendering mode: rgb (standard), depth, or collision.""" diff --git a/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer.py b/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer.py index ceee98e1cd7..5826b944c0a 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer.py +++ b/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer.py @@ -17,132 +17,62 @@ class OVVisualizer(Visualizer): - """Omniverse-based visualizer using Isaac Sim viewport. + """Omniverse visualizer using Isaac Sim viewport. - This visualizer leverages the existing Isaac Sim application and viewport for visualization. - It provides: - - Automatic rendering of the USD stage in the viewport - - Support for VisualizationMarkers (via USD prims, automatically visible) - - Support for LivePlots (via Isaac Lab UI, automatically displayed) - - Configurable viewport camera positioning - - The visualizer can operate in two modes: - 1. **Attached mode**: Uses an existing Isaac Sim app instance (typical case) - 2. **Standalone mode**: Launches a new Isaac Sim app if none exists (fallback) - - Note: - VisualizationMarkers and LivePlots are managed by the scene and environment, - not directly by this visualizer. This class primarily ensures the viewport - is configured correctly to display them. + Renders USD stage with VisualizationMarkers and LivePlots. + Can attach to existing app or launch standalone. """ def __init__(self, cfg: OVVisualizerCfg): - """Initialize OV visualizer. - - Args: - cfg: Configuration for OV visualizer. - """ super().__init__(cfg) self.cfg: OVVisualizerCfg = cfg - # Simulation app instance self._simulation_app = None self._app_launched_by_visualizer = False - - # Viewport references self._viewport_window = None self._viewport_api = None - - # Internal state self._is_initialized = False self._sim_time = 0.0 self._step_counter = 0 def initialize(self, scene_data: dict[str, Any] | None = None) -> None: - """Initialize OV visualizer with scene data. - - This method: - 1. Validates required data (USD stage) - 2. Checks if Isaac Sim app is running, launches if needed - 3. Configures the viewport camera - 4. Prepares for visualization of markers and plots - - Args: - scene_data: Scene data from SceneDataProvider. Contains: - - "usd_stage": The USD stage (required) - - "metadata": Scene metadata (physics backend, num_envs, etc.) - - Raises: - RuntimeError: If USD stage is not available. - - Note: - OV visualizer works with any physics backend (Newton, PhysX, etc.) - as long as a USD stage is available. - """ + """Initialize OV visualizer.""" if self._is_initialized: - omni.log.warn("[OVVisualizer] Already initialized. Skipping re-initialization.") + omni.log.warn("[OVVisualizer] Already initialized.") return - # Extract scene data metadata = {} usd_stage = None if scene_data is not None: usd_stage = scene_data.get("usd_stage") metadata = scene_data.get("metadata", {}) - # Validate required data if usd_stage is None: - raise RuntimeError( - "OV visualizer requires a USD stage in scene_data['usd_stage']. " - "Make sure the simulation context is initialized before creating the visualizer." - ) + raise RuntimeError("OV visualizer requires a USD stage.") - # Check if Isaac Sim app is running self._ensure_simulation_app() - - # Setup viewport self._setup_viewport(usd_stage, metadata) - # Log initialization physics_backend = metadata.get("physics_backend", "unknown") num_envs = metadata.get("num_envs", 0) - omni.log.info( - f"[OVVisualizer] Initialized with {num_envs} environments " - f"(physics: {physics_backend})" - ) + omni.log.info(f"[OVVisualizer] Initialized ({num_envs} envs, {physics_backend} physics)") self._is_initialized = True def step(self, dt: float, scene_provider: SceneDataProvider | None = None) -> None: - """Update visualizer each step. - - For the OV visualizer, most rendering is handled automatically by Isaac Sim. - This method primarily updates internal timing. - - Args: - dt: Time step in seconds. - scene_provider: Optional scene data provider (not used in minimal implementation). - """ + """Update visualizer (rendering handled automatically by Isaac Sim).""" if not self._is_initialized: - omni.log.warn("[OVVisualizer] Not initialized. Call initialize() first.") return - - # Update internal state self._sim_time += dt self._step_counter += 1 - - # Note: Viewport rendering is handled automatically by Isaac Sim's render loop - # VisualizationMarkers are updated by their respective owners - # LivePlots are updated by ManagerLiveVisualizer def close(self) -> None: """Clean up visualizer resources.""" if not self._is_initialized: return - # Close app if we launched it if self._app_launched_by_visualizer and self._simulation_app is not None: - omni.log.info("[OVVisualizer] Closing Isaac Sim app launched by visualizer.") + omni.log.info("[OVVisualizer] Closing Isaac Sim app.") self._simulation_app.close() self._simulation_app = None @@ -157,27 +87,15 @@ def is_running(self) -> bool: return self._simulation_app.is_running() def is_training_paused(self) -> bool: - """Check if training is paused. - - Note: OV visualizer does not have a built-in pause mechanism. - Returns False (never pauses training). - """ + """Check if training is paused (always False for OV).""" return False def supports_markers(self) -> bool: - """Check if this visualizer supports visualization markers. - - Returns: - True - OV visualizer supports markers via USD prims. - """ + """Supports markers via USD prims.""" return True def supports_live_plots(self) -> bool: - """Check if this visualizer supports live plots. - - Returns: - True - OV visualizer supports live plots via Isaac Lab UI. - """ + """Supports live plots via Isaac Lab UI.""" return True # ------------------------------------------------------------------ @@ -228,41 +146,48 @@ def _ensure_simulation_app(self) -> None: self._simulation_app = None def _setup_viewport(self, usd_stage, metadata: dict) -> None: - """Setup viewport with camera positioning. - - Args: - usd_stage: USD stage to display. - metadata: Scene metadata. - """ + """Setup viewport with camera and window size.""" try: - import omni.kit.viewport.utility as vp_utils - from omni.kit.viewport.utility import get_active_viewport - - # Get the active viewport - if self.cfg.viewport_name: - # Try to get specific viewport by name - self._viewport_window = get_active_viewport() # For now, use active + from omni.kit.viewport.utility import get_active_viewport, create_viewport_window + import omni.ui as ui + + # Create new viewport or use existing + if self.cfg.create_viewport and self.cfg.viewport_name: + # Create new viewport + self._viewport_window = create_viewport_window( + title=self.cfg.viewport_name, + width=self.cfg.window_width, + height=self.cfg.window_height, + ) + # Make viewport visible in UI + if self._viewport_window: + self._viewport_window.visible = True + self._viewport_window.docked = False + omni.log.info(f"[OVVisualizer] Created viewport '{self.cfg.viewport_name}'") else: + # Use existing viewport self._viewport_window = get_active_viewport() + # Try to resize if window API is available + if self._viewport_window and hasattr(self._viewport_window, 'width'): + try: + self._viewport_window.width = self.cfg.window_width + self._viewport_window.height = self.cfg.window_height + except: + pass if self._viewport_window is None: - omni.log.warn("[OVVisualizer] Could not get viewport window.") + omni.log.warn("[OVVisualizer] Could not get/create viewport.") return - # Get viewport API for camera control self._viewport_api = self._viewport_window.viewport_api - # Set camera position if specified - if self.cfg.camera_position is not None and self.cfg.camera_target is not None: - self._set_viewport_camera( - self.cfg.camera_position, - self.cfg.camera_target - ) + # Set camera + self._set_viewport_camera(self.cfg.camera_position, self.cfg.camera_target) - omni.log.info("[OVVisualizer] Viewport configured successfully.") + omni.log.info("[OVVisualizer] Viewport configured.") except ImportError as e: - omni.log.warn(f"[OVVisualizer] Viewport utilities not available: {e}") + omni.log.warn(f"[OVVisualizer] Viewport utilities unavailable: {e}") except Exception as e: omni.log.error(f"[OVVisualizer] Error setting up viewport: {e}") @@ -271,40 +196,25 @@ def _set_viewport_camera( position: tuple[float, float, float], target: tuple[float, float, float] ) -> None: - """Set viewport camera position and target. - - Args: - position: Camera position (x, y, z). - target: Camera target/look-at point (x, y, z). - """ + """Set viewport camera position and target.""" if self._viewport_api is None: return try: from pxr import Gf - # Create camera transformation eye = Gf.Vec3d(*position) target_pos = Gf.Vec3d(*target) - up = Gf.Vec3d(0, 0, 1) # Z-up - - # Set camera transform - # Note: The exact API might vary depending on Isaac Sim version - # This is a common pattern, but may need adjustment - transform = Gf.Matrix4d() - transform.SetLookAt(eye, target_pos, up) + up = Gf.Vec3d(0, 0, 1) - # Try to apply to viewport - # The API for this can vary, so we'll try a few approaches + # Try viewport API methods if hasattr(self._viewport_api, 'set_view'): self._viewport_api.set_view(eye, target_pos, up) elif hasattr(self._viewport_window, 'set_camera_position'): self._viewport_window.set_camera_position(*position, True) self._viewport_window.set_camera_target(*target, True) - omni.log.info( - f"[OVVisualizer] Set camera: pos={position}, target={target}" - ) + omni.log.info(f"[OVVisualizer] Camera: pos={position}, target={target}") except Exception as e: - omni.log.warn(f"[OVVisualizer] Could not set camera transform: {e}") + omni.log.warn(f"[OVVisualizer] Could not set camera: {e}") diff --git a/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer_cfg.py b/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer_cfg.py index 47252a87a46..b107f1cd0d4 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer_cfg.py +++ b/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer_cfg.py @@ -12,39 +12,29 @@ @configclass class OVVisualizerCfg(VisualizerCfg): - """Configuration for Omniverse-based visualizer. + """Configuration for Omniverse visualizer using Isaac Sim viewport. - This visualizer uses the Isaac Sim application viewport for visualization. - It automatically displays: - - The USD stage (all environment prims) - - VisualizationMarkers (via USD prims) - - LivePlots (via Isaac Lab UI widgets) - - The visualizer can operate in two modes: - 1. Attached mode: Uses an existing Isaac Sim app instance - 2. Standalone mode: Launches a new Isaac Sim app if none exists + Displays USD stage, VisualizationMarkers, and LivePlots. + Can attach to existing app or launch standalone. """ visualizer_type: str = "omniverse" + """Type identifier for Omniverse visualizer.""" + + viewport_name: str | None = "/OmniverseKit/Viewport" + """Viewport name to use. If None, uses active viewport.""" - # Viewport settings - viewport_name: str = "/OmniverseKit/Viewport" - """Name of the viewport to use. If None, uses the default active viewport.""" + create_viewport: bool = False + """Create new viewport with specified name and camera pose.""" - camera_position: tuple[float, float, float] | None = (10.0, 10.0, 10.0) - """Initial camera position for viewport (x, y, z). If None, keeps current camera pose.""" + window_width: int = 1920 + """Viewport width in pixels.""" - camera_target: tuple[float, float, float] | None = (0.0, 0.0, 0.0) - """Initial camera target/look-at point (x, y, z). If None, keeps current target.""" + window_height: int = 1080 + """Viewport height in pixels.""" - # App launch settings (for standalone mode) launch_app_if_missing: bool = True - """If True and no app is running, launch a new Isaac Sim app instance.""" + """Launch Isaac Sim if not already running.""" app_experience: str = "isaac-sim.python.kit" - """Isaac Sim app experience file to use when launching standalone app.""" - - # Environment visibility (for partial visualization - future use) - # NOTE: Partial visualization (REQ-11) is not implemented in this minimal version - # visualize_all_envs: bool = True - # env_indices_to_visualize: list[int] | None = None + """Isaac Sim experience file for standalone launch.""" diff --git a/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer.py b/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer.py index 6c356c4dd8c..eaa23fea369 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer.py +++ b/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer.py @@ -32,26 +32,12 @@ class NewtonViewerRerun(ViewerRerun if _RERUN_AVAILABLE else object): - """Isaac Lab wrapper around Newton's ViewerRerun. + """Isaac Lab wrapper for Newton's ViewerRerun. - This wrapper adds Isaac Lab-specific features on top of Newton's base ViewerRerun: - - - Integration with Isaac Lab's VisualizationMarkers system - - Integration with Isaac Lab's LivePlots system - - Environment metadata display - - Custom Rerun blueprint for Isaac Lab workflow - - Partial environment visualization support - - The wrapper uses composition to extend Newton's ViewerRerun without modifying - the base Newton library, similar to how NewtonViewerGL wraps ViewerGL. - - Note: - This class requires Newton physics backend and rerun-sdk to be installed. - """ + Adds VisualizationMarkers, LivePlots, metadata display, and partial visualization.""" def __init__( self, - # Newton ViewerRerun parameters server: bool = True, address: str = "127.0.0.1:9876", launch_viewer: bool = True, @@ -59,51 +45,30 @@ def __init__( keep_historical_data: bool = False, keep_scalar_history: bool = True, record_to_rrd: str | None = None, - # Isaac Lab-specific parameters - train_mode: bool = True, metadata: dict | None = None, - visualize_markers: bool = True, - visualize_plots: bool = True, + enable_markers: bool = True, + enable_live_plots: bool = True, env_indices: list[int] | None = None, ): - """Initialize Isaac Lab Rerun viewer wrapper. - - Args: - server: If True, start rerun in server mode (gRPC). - address: Address and port for rerun server mode. - launch_viewer: If True, launch a local rerun viewer client. - app_id: Application ID for rerun (defaults to 'newton-viewer'). - keep_historical_data: If True, keep historical data in the timeline. - keep_scalar_history: If True, keep historical scalar data. - record_to_rrd: Path to record viewer to .rrd file. - train_mode: Whether in training mode (affects behavior/UI). - metadata: Scene metadata (num_envs, physics backend, etc.). - visualize_markers: Whether to actively log VisualizationMarkers. - visualize_plots: Whether to actively log LivePlot data. - env_indices: Which environments to visualize (None = all). - """ + """Initialize Newton ViewerRerun wrapper.""" if not _RERUN_AVAILABLE: - raise ImportError( - "Rerun visualizer requires rerun-sdk and Newton to be installed. " - "Install with: pip install rerun-sdk" - ) + raise ImportError("Rerun visualizer requires rerun-sdk and Newton. Install: pip install rerun-sdk") - # Call parent constructor with only Newton parameters + # Call parent with only Newton parameters super().__init__( server=server, address=address, launch_viewer=launch_viewer, app_id=app_id, - # keep_historical_data=keep_historical_data, - # keep_scalar_history=keep_scalar_history, - # record_to_rrd=record_to_rrd, + keep_historical_data=keep_historical_data, + keep_scalar_history=keep_scalar_history, + record_to_rrd=record_to_rrd, ) - # Isaac Lab specific state + # Isaac Lab state self._metadata = metadata or {} - self._train_mode = train_mode - self._visualize_markers = visualize_markers - self._visualize_plots = visualize_plots + self._enable_markers = enable_markers + self._enable_live_plots = enable_live_plots self._env_indices = env_indices # Storage for registered markers and plots @@ -130,13 +95,13 @@ def _log_metadata(self) -> None: else: metadata_text += f"**Visualized Environments:** All ({num_envs})\n" - # Mode info - mode = "Training" if self._train_mode else "Inference/Play" - metadata_text += f"**Mode:** {mode}\n" + # Physics backend info + physics_backend = self._metadata.get("physics_backend", "unknown") + metadata_text += f"**Physics:** {physics_backend}\n" # Visualization features - metadata_text += f"**Markers Enabled:** {self._visualize_markers}\n" - metadata_text += f"**Plots Enabled:** {self._visualize_plots}\n" + metadata_text += f"**Markers Enabled:** {self._enable_markers}\n" + metadata_text += f"**Plots Enabled:** {self._enable_live_plots}\n" # Additional metadata for key, value in self._metadata.items(): @@ -291,67 +256,18 @@ def _log_marker_data(self, marker_data: dict, entity_path: str) -> None: class RerunVisualizer(Visualizer): - """Rerun-based visualizer for Isaac Lab using rerun-sdk. - - This visualizer provides web-based visualization with advanced features: - - - **Time Scrubbing**: Rewind and replay simulation timeline - - **Data Inspection**: Inspect transforms, meshes, and data in detail - - **Recording**: Save to .rrd files for offline analysis - - **Active Logging**: Explicitly logs markers and plots (unlike passive OV visualizer) - - The Rerun visualizer wraps Newton's ViewerRerun and requires the Newton physics - backend. It uses active logging, meaning all visualization data (markers, plots) - must be explicitly logged each frame, unlike the OV visualizer where USD-based - markers automatically appear. + """Rerun web-based visualizer with time scrubbing, recording, and data inspection. - Requirements: - - Newton physics backend (scene_data must contain Newton Model and State) - - rerun-sdk package: ``pip install rerun-sdk`` - - Future Support: - - PhysX backend support (planned for future release) - - Additional marker types (cylinders, cones, boxes) - - Full LivePlot integration (currently stub) - - Example: - - .. code-block:: python - - from isaaclab.sim import SimulationCfg - from isaaclab.sim.visualizers import RerunVisualizerCfg - - sim_cfg = SimulationCfg( - dt=0.01, - visualizers=RerunVisualizerCfg( - enabled=True, - launch_viewer=True, - keep_historical_data=False, # Constant memory - ), - ) - """ + Requires Newton physics backend and rerun-sdk (pip install rerun-sdk).""" def __init__(self, cfg: RerunVisualizerCfg): - """Initialize Rerun visualizer. - - Args: - cfg: Configuration for Rerun visualizer. - - Raises: - ImportError: If rerun-sdk or Newton is not installed. - """ + """Initialize Rerun visualizer.""" super().__init__(cfg) self.cfg: RerunVisualizerCfg = cfg - # Check dependencies if not _RERUN_AVAILABLE: - raise ImportError( - "Rerun visualizer requires rerun-sdk and Newton to be installed.\n" - "Install with: pip install rerun-sdk\n" - "Make sure Newton physics is also available in your environment." - ) + raise ImportError("Rerun visualizer requires rerun-sdk and Newton. Install: pip install rerun-sdk") - # Will be initialized in initialize() self._viewer: NewtonViewerRerun | None = None self._model = None self._state = None @@ -359,23 +275,7 @@ def __init__(self, cfg: RerunVisualizerCfg): self._sim_time = 0.0 def initialize(self, scene_data: dict[str, Any] | None = None) -> None: - """Initialize Rerun visualizer with scene data. - - This method: - 1. Validates required data (Newton Model and State) - 2. Checks physics backend compatibility - 3. Creates NewtonViewerRerun instance with Isaac Lab extensions - 4. Sets up the model for visualization - - Args: - scene_data: Scene data from SceneDataProvider. Must contain: - - "model": Newton Model (required) - - "state": Newton State (required) - - "metadata": Scene metadata (physics backend, num_envs, etc.) - - Raises: - RuntimeError: If Newton Model/State is not available or physics backend is incompatible. - """ + """Initialize visualizer with Newton Model and State.""" if self._is_initialized: omni.log.warn("[RerunVisualizer] Already initialized. Skipping re-initialization.") return @@ -421,10 +321,9 @@ def initialize(self, scene_data: dict[str, Any] | None = None) -> None: keep_historical_data=self.cfg.keep_historical_data, keep_scalar_history=self.cfg.keep_scalar_history, record_to_rrd=self.cfg.record_to_rrd, - train_mode=self.cfg.train_mode, metadata=metadata, - visualize_markers=self.cfg.visualize_markers, - visualize_plots=self.cfg.visualize_plots, + enable_markers=self.cfg.enable_markers, + enable_live_plots=self.cfg.enable_live_plots, env_indices=self.cfg.env_indices, ) diff --git a/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer_cfg.py b/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer_cfg.py index d366f1a5bfb..77b3716d036 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer_cfg.py +++ b/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer_cfg.py @@ -14,156 +14,33 @@ @configclass class RerunVisualizerCfg(VisualizerCfg): - """Configuration for the Rerun visualizer using rerun-sdk. + """Configuration for Rerun visualizer (web-based visualization). - The Rerun visualizer provides web-based visualization with advanced features: - - - Time scrubbing and playback controls - - 3D scene navigation and inspection - - Data filtering and analysis - - Recording to .rrd files for offline replay - - Built-in timeline and data inspection tools - - This visualizer requires the Newton physics backend and the rerun-sdk package: - - .. code-block:: bash - - pip install rerun-sdk - - Note: - The Rerun visualizer wraps Newton's ViewerRerun, which requires a Newton Model - and State. It will not work with other physics backends (e.g., PhysX) until - future support is added. - - Example: - - .. code-block:: python - - from isaaclab.sim.visualizers import RerunVisualizerCfg - - visualizer_cfg = RerunVisualizerCfg( - enabled=True, - server_mode=True, - launch_viewer=True, - keep_historical_data=False, # Constant memory for training - record_to_rrd="recording.rrd", # Save to file - ) + Provides time scrubbing, 3D navigation, data filtering, and .rrd recording. + Requires Newton physics backend and rerun-sdk: `pip install rerun-sdk` """ visualizer_type: str = "rerun" - """Type identifier for the Rerun visualizer. Defaults to "rerun".""" + """Type identifier for Rerun visualizer.""" - # Connection settings server_mode: bool = True - """Whether to run Rerun in server mode (gRPC). Defaults to True. - - If True, Rerun will start a gRPC server that the web viewer connects to. - If False, data is logged directly (useful for recording to file only). - """ + """Run Rerun in server mode (gRPC for web viewer).""" server_address: str = "127.0.0.1:9876" - """Server address and port for gRPC mode. Defaults to "127.0.0.1:9876". - - Only used if server_mode=True. The web viewer will connect to this address. - """ + """Server address and port for gRPC mode.""" launch_viewer: bool = True - """Whether to auto-launch the web viewer. Defaults to True. - - If True, a web browser will open showing the Rerun viewer interface. - The viewer provides 3D visualization, timeline controls, and data inspection. - """ + """Auto-launch web viewer in browser.""" app_id: str = "isaaclab-simulation" - """Application identifier for Rerun. Defaults to "isaaclab-simulation". - - This is displayed in the Rerun viewer title and used to distinguish - multiple Rerun sessions. - """ + """Application identifier shown in viewer title.""" - # Data management keep_historical_data: bool = False - """Whether to keep historical transform data in viewer timeline. Defaults to False. - - - If False: Only current frame is kept, memory usage is constant (good for training) - - If True: Full timeline is kept, enables time scrubbing (good for debugging) - - For long training runs with many environments, False is recommended to avoid - memory issues. For analysis and debugging, True allows rewinding the simulation. - """ + """Keep transform history for time scrubbing (False = constant memory for training).""" keep_scalar_history: bool = True - """Whether to keep historical scalar/plot data in viewer. Defaults to True. - - Scalar data (plots, metrics) is typically small, so keeping history is - reasonable even for long runs. This enables viewing plot trends over time. - """ - - # Recording - record_to_rrd: str | None = None - """Path to save recording as .rrd file. Defaults to None (no recording). - - If specified (e.g., "my_recording.rrd"), all logged data will be saved to - this file for offline replay and analysis. The file can be opened later with: - - .. code-block:: bash - - rerun my_recording.rrd - - Example paths: - - "recording.rrd" - saves to current directory - - "/tmp/recordings/run_{timestamp}.rrd" - absolute path with timestamp - - None - no recording saved - """ - - # Visualization options - log_transforms: bool = True - """Whether to log rigid body transforms. Defaults to True. - - Transform logging shows the position and orientation of all rigid bodies - in the scene. This is the core visualization data. - """ - - log_meshes: bool = True - """Whether to log mesh geometry. Defaults to True. - - Mesh logging shows the 3D shapes of objects. If False, only transforms - (positions/orientations) are shown as coordinate frames. - """ - - visualize_markers: bool = True - """Whether to actively log VisualizationMarkers to Rerun. Defaults to True. - - If True, markers created via VisualizationMarkers (arrows, frames, spheres, etc.) - will be converted to Rerun entities and logged each frame. This requires active - logging (unlike OV visualizer where markers auto-appear in the viewport). - - Supported marker types: - - Arrows (via log_lines) - - Coordinate frames (via log_lines for XYZ axes) - - Spheres (via log_points) - """ - - visualize_plots: bool = True - """Whether to actively log LivePlot data to Rerun. Defaults to True. - - If True, scalar data from LivePlots will be logged as time series in Rerun. - This allows viewing training metrics, rewards, and other scalars alongside - the 3D visualization. - - Note: Currently a stub - full implementation coming soon. - """ - - # Performance and filtering - max_instances_per_env: int | None = None - """Maximum number of instances to visualize per environment. Defaults to None (all). - - For scenes with many instances per environment, this limits how many are - visualized to improve performance. None means visualize all instances. - """ + """Keep scalar/plot history in timeline.""" - # Future: PhysX backend support - # When PhysX support is added, these fields will be used: - # physics_backend: Literal["newton", "physx"] | None = None - # """Physics backend to use. Auto-detected if None.""" + record_to_rrd: str | None = test.rrd + """Path to save .rrd recording file. None = no recording.""" diff --git a/source/isaaclab/isaaclab/sim/visualizers/visualizer.py b/source/isaaclab/isaaclab/sim/visualizers/visualizer.py index bbb684df68c..930cde03bcd 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/visualizer.py +++ b/source/isaaclab/isaaclab/sim/visualizers/visualizer.py @@ -19,145 +19,58 @@ class Visualizer(ABC): """Base class for all visualizer backends. - Visualizers are used for debug visualization and monitoring during simulation, - separate from rendering for sensors/cameras. Each visualizer backend (Newton OpenGL, - Omniverse, Rerun) should inherit from this class and implement the required methods. - - The visualizer lifecycle follows this pattern: - 1. __init__: Create the visualizer with configuration - 2. initialize: Set up the visualizer with the simulation model/scene - 3. step: Update the visualizer each simulation step - 4. close: Clean up resources when done - - Args: - cfg: Configuration for the visualizer backend. + Lifecycle: __init__() -> initialize() -> step() (repeated) -> close() """ def __init__(self, cfg: VisualizerCfg): - """Initialize the visualizer with configuration. - - Args: - cfg: Configuration for the visualizer backend. - """ + """Initialize visualizer with config.""" self.cfg = cfg self._is_initialized = False self._is_closed = False @abstractmethod def initialize(self, scene_data: dict[str, Any] | None = None) -> None: - """Initialize the visualizer with the simulation scene. - - This method is called once after the simulation scene is created and before - the simulation starts. It should set up any necessary resources for visualization. - - Args: - scene_data: Optional dictionary containing initial scene data. The contents - depend on what's available at initialization time. May include: - - "model": Physics model object - - "state": Initial physics state - - "usd_stage": USD stage - The visualizer should handle None or missing keys gracefully. - """ + """Initialize visualizer with scene data (model, state, usd_stage, etc.).""" pass @abstractmethod def step(self, dt: float, scene_provider: SceneDataProvider | None = None) -> None: - """Update the visualizer for one simulation step. - - This method is called each simulation step to update the visualization. - The visualizer should pull any needed data from the scene_provider. - - Args: - dt: Time step in seconds since last visualization update. - scene_provider: Provider for accessing current scene data (physics state, USD stage, etc.). - Visualizers should query this for updated data rather than directly - accessing physics managers. May be None if no scene data is available yet. - """ + """Update visualization for one step.""" pass @abstractmethod def close(self) -> None: - """Close the visualizer and clean up resources. - - This method is called when the simulation is ending or the visualizer - is no longer needed. It should release any resources held by the visualizer. - """ + """Clean up resources.""" pass @abstractmethod def is_running(self) -> bool: - """Check if the visualizer is still running. - - Returns: - True if the visualizer is running and should continue receiving updates, - False if it has been closed (e.g., user closed the window). - """ + """Check if visualizer is still running (e.g., window not closed).""" pass def is_training_paused(self) -> bool: - """Check if training/simulation is paused by the visualizer. - - Some visualizers (like Newton OpenGL) provide controls to pause the simulation - while keeping the visualizer running. This is useful for debugging. - - Returns: - True if the user has paused training/simulation, False otherwise. - Default implementation returns False (no pause support). - """ + """Check if training is paused by visualizer controls.""" return False def is_rendering_paused(self) -> bool: - """Check if rendering is paused by the visualizer. - - Some visualizers allow pausing rendering while keeping simulation running, - which can improve performance during training. - - Returns: - True if rendering is paused, False otherwise. - Default implementation returns False (no pause support). - """ + """Check if rendering is paused by visualizer controls.""" return False @property def is_initialized(self) -> bool: - """Check if the visualizer has been initialized. - - Returns: - True if initialize() has been called successfully. - """ + """Check if initialize() has been called.""" return self._is_initialized @property def is_closed(self) -> bool: - """Check if the visualizer has been closed. - - Returns: - True if close() has been called. - """ + """Check if close() has been called.""" return self._is_closed def supports_markers(self) -> bool: - """Check if this visualizer supports visualization markers. - - Visualization markers are geometric shapes (spheres, arrows, frames, etc.) - used for debug visualization. They are typically managed by the scene/environment - but rendered by the visualizer. - - Returns: - True if the visualizer can display VisualizationMarkers, False otherwise. - Default implementation returns False. - """ + """Check if visualizer supports VisualizationMarkers.""" return False def supports_live_plots(self) -> bool: - """Check if this visualizer supports live plots. - - Live plots display time-series data (observations, rewards, etc.) in real-time - via UI widgets. They are typically managed by manager-based environments. - - Returns: - True if the visualizer can display live plots, False otherwise. - Default implementation returns False. - """ + """Check if visualizer supports LivePlots.""" return False diff --git a/source/isaaclab/isaaclab/sim/visualizers/visualizer_cfg.py b/source/isaaclab/isaaclab/sim/visualizers/visualizer_cfg.py index 76d54673105..5d494f1839b 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/visualizer_cfg.py +++ b/source/isaaclab/isaaclab/sim/visualizers/visualizer_cfg.py @@ -17,108 +17,43 @@ @configclass class VisualizerCfg: - """Base configuration for visualizer backends. - - This is the base class for all visualizer configurations. Visualizers are used - for debug visualization and monitoring during simulation, separate from rendering - for sensors/cameras. - - All visualizer backends should inherit from this class and add their specific - configuration parameters. - """ + """Base configuration for all visualizer backends.""" visualizer_type: str = "base" - """Type identifier for this visualizer (e.g., 'newton', 'rerun', 'omniverse'). - - This is used by the factory pattern to instantiate the correct visualizer class. - Subclasses should override this with their specific type identifier. - """ + """Type identifier (e.g., 'newton', 'rerun', 'omniverse').""" enabled: bool = False - """Whether the visualizer is enabled. Default is False.""" + """Whether the visualizer is enabled.""" update_frequency: int = 1 - """Frequency of updates to the visualizer (in simulation steps). - - Higher values (e.g., 10) mean the visualizer updates less frequently, improving - performance at the cost of less responsive visualization. Lower values (e.g., 1) - provide more responsive visualization but may impact performance. - Default is 1 (update every step). - """ + """Update frequency in simulation steps (1 = every step).""" env_indices: list[int] | None = None - """List of environment indices to visualize. Default is None. - - If None, all environments will be visualized. If a list is provided, only the - specified environments will be visualized. This is useful for reducing the - visualization overhead when running with many environments. - - Example: [0, 1, 2] will visualize only the first 3 environments. - """ + """Environment indices to visualize. None = all environments.""" enable_markers: bool = True - """Whether to enable visualization markers (debug drawing). Default is True. - - Visualization markers are used for debug drawing of points, lines, frames, etc. - These correspond to the VisualizationMarkers class in isaaclab.markers. - """ + """Enable visualization markers (debug drawing).""" enable_live_plots: bool = True - """Whether to enable live plotting of data. Default is True. - - Live plots can be used to visualize real-time data such as observations, - rewards, and other metrics during simulation. - """ - - train_mode: bool = True - """Whether the visualizer is in training mode (True) or play/inference mode (False). - - This affects the UI and controls displayed in the visualizer. In training mode, - additional controls may be shown for pausing training, adjusting update frequency, etc. - Default is True. - """ + """Enable live plotting of data.""" camera_position: tuple[float, float, float] = (10.0, 0.0, 3.0) - """Initial position of the camera in the visualizer. Default is (10.0, 0.0, 3.0).""" + """Initial camera position (x, y, z).""" camera_target: tuple[float, float, float] = (0.0, 0.0, 0.0) - """Initial target (look-at point) of the camera. Default is (0.0, 0.0, 0.0).""" - - window_width: int = 1920 - """Width of the visualizer window in pixels. Default is 1920.""" - - window_height: int = 1080 - """Height of the visualizer window in pixels. Default is 1080.""" + """Initial camera target/look-at point (x, y, z).""" def get_visualizer_type(self) -> str: - """Get the type of visualizer as a string. - - Returns: - String identifier for the visualizer type. - """ + """Get the visualizer type identifier.""" return self.visualizer_type def create_visualizer(self) -> Visualizer: - """Factory method to create a visualizer instance from this configuration. - - This method uses the visualizer registry to instantiate the appropriate - visualizer class based on the `visualizer_type` field. - - Returns: - Visualizer instance configured with this config. - - Raises: - ValueError: If the visualizer type is not registered. - """ - # Import here to avoid circular imports + """Create visualizer instance from this config using factory pattern.""" from . import get_visualizer_class visualizer_class = get_visualizer_class(self.visualizer_type) if visualizer_class is None: - raise ValueError( - f"Visualizer type '{self.visualizer_type}' is not registered. " - f"Make sure the visualizer module is imported." - ) + raise ValueError(f"Visualizer type '{self.visualizer_type}' is not registered.") return visualizer_class(self) diff --git a/source/isaaclab/setup.py b/source/isaaclab/setup.py index f487b388bde..c332f1468c0 100644 --- a/source/isaaclab/setup.py +++ b/source/isaaclab/setup.py @@ -50,12 +50,12 @@ "usd-core==25.05.0", "mujoco>=3.3.8.dev821851540", "mujoco-warp @ git+https://github.com/google-deepmind/mujoco_warp.git@bbd757cace561de47512b560517ee728c8416de5", - "newton @ git+https://github.com/newton-physics/newton.git@15b9955bafa61f8fcb40c17dc00f0b552d3c65ca", + # "newton @ git+https://github.com/newton-physics/newton.git@15b9955bafa61f8fcb40c17dc00f0b552d3c65ca", + "newton @ git+https://github.com/newton-physics/newton.git@c4baa06c3e8ea0a3090037b2b197e9aa453265f1", "imgui-bundle==1.92.0", "PyOpenGL-accelerate==3.1.10", ] - # Additional dependencies that are only available on Linux platforms if platform.system() == "Linux": INSTALL_REQUIRES += [ From 95d9429ce23feaa9625acb8b0a0b0e25927ca682 Mon Sep 17 00:00:00 2001 From: mtrepte Date: Fri, 14 Nov 2025 18:29:45 -0800 Subject: [PATCH 09/24] clean --- .../sim/visualizers/newton_visualizer.py | 51 +--------------- .../sim/visualizers/newton_visualizer_cfg.py | 6 ++ .../isaaclab/sim/visualizers/ov_visualizer.py | 59 +++++++++---------- .../sim/visualizers/ov_visualizer_cfg.py | 14 +++-- .../sim/visualizers/rerun_visualizer.py | 36 ++++++----- .../sim/visualizers/rerun_visualizer_cfg.py | 4 +- .../sim/visualizers/visualizer_cfg.py | 9 --- 7 files changed, 70 insertions(+), 109 deletions(-) diff --git a/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py b/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py index 6314e6744f3..590b21b13dd 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py +++ b/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py @@ -34,7 +34,6 @@ def __init__(self, *args, metadata: dict | None = None, **kwargs): self._paused_training: bool = False self._paused_rendering: bool = False self._fallback_draw_controls: bool = False - self._visualizer_update_frequency: int = 1 self._metadata = metadata or {} try: @@ -50,22 +49,6 @@ def is_rendering_paused(self) -> bool: """Check if rendering is paused.""" return self._paused_rendering - def set_visualizer_update_frequency(self, frequency: int) -> None: - """Set the visualizer update frequency. - - Args: - frequency: Number of simulation steps between visualizer updates. - """ - self._visualizer_update_frequency = max(1, frequency) - - def get_visualizer_update_frequency(self) -> int: - """Get the current visualizer update frequency. - - Returns: - Number of simulation steps between visualizer updates. - """ - return self._visualizer_update_frequency - # UI callback rendered inside the "Example Options" panel of the left sidebar def _render_training_controls(self, imgui): imgui.separator() @@ -79,21 +62,6 @@ def _render_training_controls(self, imgui): if imgui.button(rendering_label): self._paused_rendering = not self._paused_rendering - imgui.text("Visualizer Update Frequency") - - current_frequency = self._visualizer_update_frequency - changed, new_frequency = imgui.slider_int( - "##VisualizerUpdateFreq", current_frequency, 1, 20, f"Every {current_frequency} frames" - ) - if changed: - self._visualizer_update_frequency = new_frequency - - if imgui.is_item_hovered(): - imgui.set_tooltip( - "Controls visualizer update frequency\nlower values-> more responsive visualizer but slower" - " training\nhigher values-> less responsive visualizer but faster training" - ) - # Override only SPACE key to use rendering pause, preserve all other shortcuts def on_key_press(self, symbol, modifiers): if self.ui.is_capturing(): @@ -341,24 +309,13 @@ def initialize(self, scene_data: dict[str, Any] | None = None) -> None: self._viewer.renderer.sky_lower = self.cfg.ground_color self._viewer.renderer._light_color = self.cfg.light_color - # Set update frequency - self._viewer.set_visualizer_update_frequency(self.cfg.update_frequency) - self._is_initialized = True def step(self, dt: float, scene_provider: SceneDataProvider | None = None) -> None: """Update the visualizer for one simulation step. - Args: - dt: Time step in seconds since last visualization update. - scene_provider: Provider for accessing current scene data. The visualizer - will pull the latest Newton state from this provider. - - Note: - Pause handling (training and rendering) is managed by SimulationContext. - This method only performs the actual rendering when called. - The visualizer MUST be called every frame to maintain proper ImGui state, - even if we skip rendering some frames based on update_frequency. + Note: The visualizer MUST be called every frame to maintain proper ImGui state. + Pause handling (training and rendering) is managed by SimulationContext. """ if not self._is_initialized or self._is_closed or self._viewer is None: return @@ -370,9 +327,7 @@ def step(self, dt: float, scene_provider: SceneDataProvider | None = None) -> No if scene_provider is not None: self._state = scene_provider.get_state() - # Render the current frame - # Note: We always call begin_frame/end_frame to maintain ImGui state - # The update frequency is handled internally by the viewer + # Render the current frame (always call to maintain ImGui state) try: self._viewer.begin_frame(self._sim_time) try: diff --git a/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer_cfg.py b/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer_cfg.py index ccbd183ac80..eeca2a53736 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer_cfg.py +++ b/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer_cfg.py @@ -31,6 +31,12 @@ class NewtonVisualizerCfg(VisualizerCfg): window_height: int = 1080 """Window height in pixels.""" + camera_position: tuple[float, float, float] = (10.0, 0.0, 3.0) + """Initial camera position (x, y, z).""" + + camera_target: tuple[float, float, float] = (0.0, 0.0, 0.0) + """Initial camera target/look-at point (x, y, z).""" + # Newton-specific settings fps: int = 60 """Target FPS.""" diff --git a/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer.py b/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer.py index 5826b944c0a..ae83ae90be8 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer.py +++ b/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer.py @@ -148,43 +148,35 @@ def _ensure_simulation_app(self) -> None: def _setup_viewport(self, usd_stage, metadata: dict) -> None: """Setup viewport with camera and window size.""" try: - from omni.kit.viewport.utility import get_active_viewport, create_viewport_window - import omni.ui as ui + import omni.kit.viewport.utility as vp_utils # Create new viewport or use existing if self.cfg.create_viewport and self.cfg.viewport_name: - # Create new viewport - self._viewport_window = create_viewport_window( - title=self.cfg.viewport_name, + # Create new viewport with proper API + self._viewport_window = vp_utils.create_viewport_window( + name=self.cfg.viewport_name, width=self.cfg.window_width, height=self.cfg.window_height, + position_x=50, # Window position on screen + position_y=50, ) - # Make viewport visible in UI - if self._viewport_window: - self._viewport_window.visible = True - self._viewport_window.docked = False omni.log.info(f"[OVVisualizer] Created viewport '{self.cfg.viewport_name}'") else: - # Use existing viewport - self._viewport_window = get_active_viewport() - # Try to resize if window API is available - if self._viewport_window and hasattr(self._viewport_window, 'width'): - try: - self._viewport_window.width = self.cfg.window_width - self._viewport_window.height = self.cfg.window_height - except: - pass + # Use existing active viewport + self._viewport_window = vp_utils.get_active_viewport_window() + omni.log.info("[OVVisualizer] Using existing active viewport") if self._viewport_window is None: omni.log.warn("[OVVisualizer] Could not get/create viewport.") return + # Get viewport API for camera control self._viewport_api = self._viewport_window.viewport_api - # Set camera + # Set camera pose using Isaac Sim utility self._set_viewport_camera(self.cfg.camera_position, self.cfg.camera_target) - omni.log.info("[OVVisualizer] Viewport configured.") + omni.log.info(f"[OVVisualizer] Viewport configured (size: {self.cfg.window_width}x{self.cfg.window_height})") except ImportError as e: omni.log.warn(f"[OVVisualizer] Viewport utilities unavailable: {e}") @@ -196,25 +188,28 @@ def _set_viewport_camera( position: tuple[float, float, float], target: tuple[float, float, float] ) -> None: - """Set viewport camera position and target.""" + """Set viewport camera position and target using Isaac Sim utilities.""" if self._viewport_api is None: return try: - from pxr import Gf + # Import Isaac Sim viewport utilities + import isaacsim.core.utils.viewports as vp_utils - eye = Gf.Vec3d(*position) - target_pos = Gf.Vec3d(*target) - up = Gf.Vec3d(0, 0, 1) + # Get the camera prim path for this viewport + camera_path = self._viewport_api.get_active_camera() + if not camera_path: + camera_path = "/OmniverseKit_Persp" # Default camera - # Try viewport API methods - if hasattr(self._viewport_api, 'set_view'): - self._viewport_api.set_view(eye, target_pos, up) - elif hasattr(self._viewport_window, 'set_camera_position'): - self._viewport_window.set_camera_position(*position, True) - self._viewport_window.set_camera_target(*target, True) + # Use Isaac Sim utility to set camera view + vp_utils.set_camera_view( + eye=list(position), + target=list(target), + camera_prim_path=camera_path, + viewport_api=self._viewport_api + ) - omni.log.info(f"[OVVisualizer] Camera: pos={position}, target={target}") + omni.log.info(f"[OVVisualizer] Camera set: pos={position}, target={target}, camera={camera_path}") except Exception as e: omni.log.warn(f"[OVVisualizer] Could not set camera: {e}") diff --git a/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer_cfg.py b/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer_cfg.py index b107f1cd0d4..c75328028fc 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer_cfg.py +++ b/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer_cfg.py @@ -21,18 +21,24 @@ class OVVisualizerCfg(VisualizerCfg): visualizer_type: str = "omniverse" """Type identifier for Omniverse visualizer.""" - viewport_name: str | None = "/OmniverseKit/Viewport" + viewport_name: str | None = "Goldenstate" # "/OmniverseKit/Viewport" """Viewport name to use. If None, uses active viewport.""" - create_viewport: bool = False + create_viewport: bool = True #False """Create new viewport with specified name and camera pose.""" - window_width: int = 1920 + window_width: int = 777 # 1920 """Viewport width in pixels.""" - window_height: int = 1080 + window_height: int = 777 # 1080 """Viewport height in pixels.""" + camera_position: tuple[float, float, float] = (10.0, 10.0, 10.0) + """Initial camera position (x, y, z).""" + + camera_target: tuple[float, float, float] = (0.0, 0.0, 0.0) + """Initial camera target/look-at point (x, y, z).""" + launch_app_if_missing: bool = True """Launch Isaac Sim if not already running.""" diff --git a/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer.py b/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer.py index eaa23fea369..a6438e76a38 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer.py +++ b/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer.py @@ -60,9 +60,9 @@ def __init__( address=address, launch_viewer=launch_viewer, app_id=app_id, - keep_historical_data=keep_historical_data, - keep_scalar_history=keep_scalar_history, - record_to_rrd=record_to_rrd, + # keep_historical_data=keep_historical_data, + # keep_scalar_history=keep_scalar_history, + # record_to_rrd=record_to_rrd, ) # Isaac Lab state @@ -117,7 +117,7 @@ def register_markers(self, markers: Any) -> None: Args: markers: VisualizationMarkers instance to log each frame. """ - if self._visualize_markers: + if self._enable_markers: self._registered_markers.append(markers) omni.log.info(f"[RerunVisualizer] Registered markers: {markers}") @@ -127,7 +127,7 @@ def register_plots(self, plots: dict[str, Any]) -> None: Args: plots: Dictionary mapping plot names to LivePlot instances. """ - if self._visualize_plots: + if self._enable_live_plots: self._registered_plots.update(plots) omni.log.info(f"[RerunVisualizer] Registered {len(plots)} plot(s)") @@ -151,7 +151,7 @@ def log_markers(self) -> None: - Optimize batch logging for large marker counts - Add color/material support for better visual distinction """ - if not self._visualize_markers or len(self._registered_markers) == 0: + if not self._enable_markers or len(self._registered_markers) == 0: return try: @@ -190,7 +190,7 @@ def log_plot_data(self) -> None: - Maintain proper timeline synchronization - Support different plot types (line, bar, etc.) """ - if not self._visualize_plots or len(self._registered_plots) == 0: + if not self._enable_live_plots or len(self._registered_plots) == 0: return try: @@ -313,6 +313,9 @@ def initialize(self, scene_data: dict[str, Any] | None = None) -> None: # Create Newton ViewerRerun wrapper try: + if self.cfg.record_to_rrd: + omni.log.info(f"[RerunVisualizer] Recording enabled to: {self.cfg.record_to_rrd}") + self._viewer = NewtonViewerRerun( server=self.cfg.server_mode, address=self.cfg.server_address, @@ -389,11 +392,11 @@ def step(self, dt: float, scene_provider: SceneDataProvider | None = None) -> No self._viewer.log_state(self._state) # Actively log markers (if enabled) - if self.cfg.visualize_markers: + if self.cfg.enable_markers: self._viewer.log_markers() # Actively log plot data (if enabled) - if self.cfg.visualize_plots: + if self.cfg.enable_live_plots: self._viewer.log_plot_data() # End frame @@ -403,17 +406,22 @@ def step(self, dt: float, scene_provider: SceneDataProvider | None = None) -> No self._sim_time += dt def close(self) -> None: - """Clean up Rerun visualizer resources. - - This closes the Rerun viewer, disconnects from the server, and - finalizes any recording files. - """ + """Clean up Rerun visualizer resources and finalize recordings.""" if not self._is_initialized or self._viewer is None: return try: + if self.cfg.record_to_rrd: + omni.log.info(f"[RerunVisualizer] Finalizing recording to: {self.cfg.record_to_rrd}") self._viewer.close() omni.log.info("[RerunVisualizer] Closed successfully.") + if self.cfg.record_to_rrd: + import os + if os.path.exists(self.cfg.record_to_rrd): + size = os.path.getsize(self.cfg.record_to_rrd) + omni.log.info(f"[RerunVisualizer] Recording saved: {self.cfg.record_to_rrd} ({size} bytes)") + else: + omni.log.warn(f"[RerunVisualizer] Recording file not found: {self.cfg.record_to_rrd}") except Exception as e: omni.log.warn(f"[RerunVisualizer] Error during close: {e}") diff --git a/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer_cfg.py b/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer_cfg.py index 77b3716d036..f722ee4a746 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer_cfg.py +++ b/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer_cfg.py @@ -35,12 +35,12 @@ class RerunVisualizerCfg(VisualizerCfg): app_id: str = "isaaclab-simulation" """Application identifier shown in viewer title.""" - keep_historical_data: bool = False + keep_historical_data: bool = True """Keep transform history for time scrubbing (False = constant memory for training).""" keep_scalar_history: bool = True """Keep scalar/plot history in timeline.""" - record_to_rrd: str | None = test.rrd + record_to_rrd: str | None = "/tmp/test.rrd" """Path to save .rrd recording file. None = no recording.""" diff --git a/source/isaaclab/isaaclab/sim/visualizers/visualizer_cfg.py b/source/isaaclab/isaaclab/sim/visualizers/visualizer_cfg.py index 5d494f1839b..afc618780c7 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/visualizer_cfg.py +++ b/source/isaaclab/isaaclab/sim/visualizers/visualizer_cfg.py @@ -25,9 +25,6 @@ class VisualizerCfg: enabled: bool = False """Whether the visualizer is enabled.""" - update_frequency: int = 1 - """Update frequency in simulation steps (1 = every step).""" - env_indices: list[int] | None = None """Environment indices to visualize. None = all environments.""" @@ -37,12 +34,6 @@ class VisualizerCfg: enable_live_plots: bool = True """Enable live plotting of data.""" - camera_position: tuple[float, float, float] = (10.0, 0.0, 3.0) - """Initial camera position (x, y, z).""" - - camera_target: tuple[float, float, float] = (0.0, 0.0, 0.0) - """Initial camera target/look-at point (x, y, z).""" - def get_visualizer_type(self) -> str: """Get the visualizer type identifier.""" return self.visualizer_type From f1ca9db4459427e250fd2611244198021ac273ba Mon Sep 17 00:00:00 2001 From: mtrepte Date: Tue, 18 Nov 2025 23:03:55 -0800 Subject: [PATCH 10/24] try new newton --- .../isaaclab/isaaclab/sim/simulation_cfg.py | 4 +- .../isaaclab/sim/visualizers/ov_visualizer.py | 217 ++++++++++++++---- .../sim/visualizers/ov_visualizer_cfg.py | 13 +- source/isaaclab/setup.py | 2 +- 4 files changed, 179 insertions(+), 57 deletions(-) diff --git a/source/isaaclab/isaaclab/sim/simulation_cfg.py b/source/isaaclab/isaaclab/sim/simulation_cfg.py index dc445985978..22c13a60670 100644 --- a/source/isaaclab/isaaclab/sim/simulation_cfg.py +++ b/source/isaaclab/isaaclab/sim/simulation_cfg.py @@ -198,9 +198,9 @@ class SimulationCfg: """Render settings. Default is RenderCfg().""" # visualizers: list[VisualizerCfg] | VisualizerCfg | None = NewtonVisualizerCfg(enabled=True) - # visualizers: list[VisualizerCfg] | VisualizerCfg | None = OVVisualizerCfg(enabled=True) + visualizers: list[VisualizerCfg] | VisualizerCfg | None = OVVisualizerCfg(enabled=True) # visualizers: list[VisualizerCfg] | VisualizerCfg | None = RerunVisualizerCfg(enabled=True) - visualizers: list[VisualizerCfg] | VisualizerCfg | None = [NewtonVisualizerCfg(enabled=True), RerunVisualizerCfg(enabled=True)] + # visualizers: list[VisualizerCfg] | VisualizerCfg | None = [NewtonVisualizerCfg(enabled=True), RerunVisualizerCfg(enabled=True)] """Visualizer settings. Default is Newton (no visualizer). This field supports multiple visualizer backends for debug visualization and monitoring diff --git a/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer.py b/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer.py index ae83ae90be8..5163cfbe7d5 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer.py +++ b/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer.py @@ -7,6 +7,7 @@ from __future__ import annotations +import asyncio import omni.log from typing import Any @@ -28,7 +29,6 @@ def __init__(self, cfg: OVVisualizerCfg): self.cfg: OVVisualizerCfg = cfg self._simulation_app = None - self._app_launched_by_visualizer = False self._viewport_window = None self._viewport_api = None self._is_initialized = False @@ -71,11 +71,8 @@ def close(self) -> None: if not self._is_initialized: return - if self._app_launched_by_visualizer and self._simulation_app is not None: - omni.log.info("[OVVisualizer] Closing Isaac Sim app.") - self._simulation_app.close() - self._simulation_app = None - + # Note: We don't close the SimulationApp here as it's managed by AppLauncher + self._simulation_app = None self._viewport_window = None self._viewport_api = None self._is_initialized = False @@ -103,68 +100,115 @@ def supports_live_plots(self) -> bool: # ------------------------------------------------------------------ def _ensure_simulation_app(self) -> None: - """Ensure Isaac Sim app is running, launch if needed.""" - # Try to get existing SimulationApp instance - try: - from isaacsim import SimulationApp - - # Check if there's an existing app instance - # SimulationApp uses a singleton pattern - if hasattr(SimulationApp, '_instance') and SimulationApp._instance is not None: - self._simulation_app = SimulationApp._instance - omni.log.info("[OVVisualizer] Using existing Isaac Sim app instance.") - return - except ImportError: - omni.log.warn("[OVVisualizer] Could not import SimulationApp. May not be available.") + """Ensure Isaac Sim app is running. - # If we get here, no app is running - if not self.cfg.launch_app_if_missing: - omni.log.warn( - "[OVVisualizer] No Isaac Sim app is running and launch_app_if_missing=False. " - "Visualizer may not function correctly." - ) - return + The OV visualizer requires Isaac Sim to be launched via AppLauncher before initialization. + In typical usage (e.g., training scripts), AppLauncher handles this automatically. - # Launch a new app - omni.log.info("[OVVisualizer] No Isaac Sim app found. Launching new instance...") + Note: Future enhancement could add standalone app launching for non-training workflows, + but this is not currently needed as AppLauncher is always used in practice. + """ try: - from isaacsim import SimulationApp - - # Launch app with minimal config - launch_config = { - "headless": False, - "experience": self.cfg.app_experience, - } + # Check if omni.kit.app is available (indicates Isaac Sim is running) + import omni.kit.app - self._simulation_app = SimulationApp(launch_config) - self._app_launched_by_visualizer = True + # Get the running app instance + app = omni.kit.app.get_app() + if app is None or not app.is_running(): + raise RuntimeError( + "[OVVisualizer] No Isaac Sim app is running. " + "OV visualizer requires Isaac Sim to be launched via AppLauncher before initialization. " + "Ensure your script calls AppLauncher before creating the environment." + ) - omni.log.info(f"[OVVisualizer] Launched Isaac Sim app with experience: {self.cfg.app_experience}") + # Try to get SimulationApp instance for headless check + try: + from isaacsim import SimulationApp + + # Check various ways SimulationApp might store its instance + sim_app = None + if hasattr(SimulationApp, '_instance') and SimulationApp._instance is not None: + sim_app = SimulationApp._instance + elif hasattr(SimulationApp, 'instance') and callable(SimulationApp.instance): + sim_app = SimulationApp.instance() + + if sim_app is not None: + self._simulation_app = sim_app + + # Check if running in headless mode + if self._simulation_app.config.get("headless", False): + omni.log.warn( + "[OVVisualizer] Running in headless mode. " + "OV visualizer requires GUI mode (launch with --headless=False) to create viewports." + ) + else: + omni.log.info("[OVVisualizer] Using existing Isaac Sim app instance.") + else: + # App is running but we couldn't get SimulationApp instance + # This is okay - we can still use omni APIs + omni.log.info("[OVVisualizer] Isaac Sim app is running (via omni.kit.app).") + + except ImportError: + # SimulationApp not available, but omni.kit.app is running + omni.log.info("[OVVisualizer] Using running Isaac Sim app (SimulationApp module not available).") - except Exception as e: - omni.log.error(f"[OVVisualizer] Failed to launch Isaac Sim app: {e}") - self._simulation_app = None + except ImportError as e: + raise ImportError( + f"[OVVisualizer] Could not import omni.kit.app: {e}. " + "Isaac Sim may not be installed or not running." + ) def _setup_viewport(self, usd_stage, metadata: dict) -> None: """Setup viewport with camera and window size.""" try: import omni.kit.viewport.utility as vp_utils + from omni.ui import DockPosition # Create new viewport or use existing if self.cfg.create_viewport and self.cfg.viewport_name: + # Map dock position string to enum + dock_position_map = { + "LEFT": DockPosition.LEFT, + "RIGHT": DockPosition.RIGHT, + "BOTTOM": DockPosition.BOTTOM, + "SAME": DockPosition.SAME, + } + dock_pos = dock_position_map.get(self.cfg.dock_position.upper(), DockPosition.SAME) + # Create new viewport with proper API self._viewport_window = vp_utils.create_viewport_window( name=self.cfg.viewport_name, width=self.cfg.window_width, height=self.cfg.window_height, - position_x=50, # Window position on screen + position_x=50, position_y=50, + docked=True, ) + omni.log.info(f"[OVVisualizer] Created viewport '{self.cfg.viewport_name}'") + + # Dock the viewport asynchronously (needs to wait for window creation) + asyncio.ensure_future(self._dock_viewport_async(self.cfg.viewport_name, dock_pos)) + + # Create dedicated camera for this viewport + if self._viewport_window: + self._create_and_assign_camera(usd_stage) else: - # Use existing active viewport - self._viewport_window = vp_utils.get_active_viewport_window() - omni.log.info("[OVVisualizer] Using existing active viewport") + # Use existing viewport by name, or fall back to active viewport + if self.cfg.viewport_name: + self._viewport_window = vp_utils.get_viewport_window_by_name(self.cfg.viewport_name) + + if self._viewport_window is None: + omni.log.warn( + f"[OVVisualizer] Viewport '{self.cfg.viewport_name}' not found. " + f"Using active viewport instead." + ) + self._viewport_window = vp_utils.get_active_viewport_window() + else: + omni.log.info(f"[OVVisualizer] Using existing viewport '{self.cfg.viewport_name}'") + else: + self._viewport_window = vp_utils.get_active_viewport_window() + omni.log.info("[OVVisualizer] Using existing active viewport") if self._viewport_window is None: omni.log.warn("[OVVisualizer] Could not get/create viewport.") @@ -173,7 +217,7 @@ def _setup_viewport(self, usd_stage, metadata: dict) -> None: # Get viewport API for camera control self._viewport_api = self._viewport_window.viewport_api - # Set camera pose using Isaac Sim utility + # Set camera pose (uses existing camera if not created above) self._set_viewport_camera(self.cfg.camera_position, self.cfg.camera_target) omni.log.info(f"[OVVisualizer] Viewport configured (size: {self.cfg.window_width}x{self.cfg.window_height})") @@ -183,6 +227,87 @@ def _setup_viewport(self, usd_stage, metadata: dict) -> None: except Exception as e: omni.log.error(f"[OVVisualizer] Error setting up viewport: {e}") + async def _dock_viewport_async(self, viewport_name: str, dock_position) -> None: + """Dock viewport window asynchronously after it's created. + + Args: + viewport_name: Name of the viewport window to dock. + dock_position: DockPosition enum value for where to dock. + """ + try: + import omni.ui + import omni.kit.app + + # Wait for the viewport window to be created in the workspace + viewport_window = None + for i in range(10): # Try up to 10 frames + viewport_window = omni.ui.Workspace.get_window(viewport_name) + if viewport_window: + omni.log.info(f"[OVVisualizer] Found viewport window '{viewport_name}' after {i} frames") + break + await omni.kit.app.get_app().next_update_async() + + if not viewport_window: + omni.log.warn(f"[OVVisualizer] Could not find viewport window '{viewport_name}' in workspace for docking.") + return + + # Get the main viewport to dock relative to + main_viewport = omni.ui.Workspace.get_window("Viewport") + if not main_viewport: + # Try alternative viewport names + for alt_name in ["/OmniverseKit/Viewport", "Viewport Next"]: + main_viewport = omni.ui.Workspace.get_window(alt_name) + if main_viewport: + break + + if main_viewport and main_viewport != viewport_window: + # Dock the new viewport relative to the main viewport + viewport_window.dock_in(main_viewport, dock_position, 0.5) + + # Wait a frame for docking to complete + await omni.kit.app.get_app().next_update_async() + + # Make the new viewport the active/focused tab + # Try multiple methods to ensure it becomes active + viewport_window.focus() + viewport_window.visible = True + + # Wait another frame and focus again (sometimes needed for tabs) + await omni.kit.app.get_app().next_update_async() + viewport_window.focus() + + omni.log.info(f"[OVVisualizer] Docked viewport '{viewport_name}' at position {self.cfg.dock_position} and set as active") + else: + omni.log.info(f"[OVVisualizer] Could not find main viewport for docking. Viewport '{viewport_name}' will remain floating.") + + except Exception as e: + omni.log.warn(f"[OVVisualizer] Error docking viewport: {e}") + + def _create_and_assign_camera(self, usd_stage) -> None: + """Create a dedicated camera for this viewport and assign it.""" + try: + from pxr import UsdGeom, Gf + + # Create camera prim path based on viewport name + camera_path = f"/World/Cameras/{self.cfg.viewport_name}_Camera" + + # Check if camera already exists + camera_prim = usd_stage.GetPrimAtPath(camera_path) + if not camera_prim.IsValid(): + # Create camera prim + camera = UsdGeom.Camera.Define(usd_stage, camera_path) + omni.log.info(f"[OVVisualizer] Created camera: {camera_path}") + else: + omni.log.info(f"[OVVisualizer] Using existing camera: {camera_path}") + + # Assign camera to viewport + if self._viewport_api: + self._viewport_api.set_active_camera(camera_path) + omni.log.info(f"[OVVisualizer] Assigned camera '{camera_path}' to viewport '{self.cfg.viewport_name}'") + + except Exception as e: + omni.log.warn(f"[OVVisualizer] Could not create/assign camera: {e}. Using default camera.") + def _set_viewport_camera( self, position: tuple[float, float, float], diff --git a/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer_cfg.py b/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer_cfg.py index c75328028fc..40a57db5391 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer_cfg.py +++ b/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer_cfg.py @@ -21,26 +21,23 @@ class OVVisualizerCfg(VisualizerCfg): visualizer_type: str = "omniverse" """Type identifier for Omniverse visualizer.""" - viewport_name: str | None = "Goldenstate" # "/OmniverseKit/Viewport" + viewport_name: str | None = "Visualizer" """Viewport name to use. If None, uses active viewport.""" create_viewport: bool = True #False """Create new viewport with specified name and camera pose.""" + dock_position: str = "SAME" + """Dock position for new viewport. Options: 'LEFT', 'RIGHT', 'BOTTOM', 'SAME' (tabs with existing).""" + window_width: int = 777 # 1920 """Viewport width in pixels.""" window_height: int = 777 # 1080 """Viewport height in pixels.""" - camera_position: tuple[float, float, float] = (10.0, 10.0, 10.0) + camera_position: tuple[float, float, float] = (10.0, 10.0, 3.0) """Initial camera position (x, y, z).""" camera_target: tuple[float, float, float] = (0.0, 0.0, 0.0) """Initial camera target/look-at point (x, y, z).""" - - launch_app_if_missing: bool = True - """Launch Isaac Sim if not already running.""" - - app_experience: str = "isaac-sim.python.kit" - """Isaac Sim experience file for standalone launch.""" diff --git a/source/isaaclab/setup.py b/source/isaaclab/setup.py index c332f1468c0..5421d4e6e85 100644 --- a/source/isaaclab/setup.py +++ b/source/isaaclab/setup.py @@ -51,7 +51,7 @@ "mujoco>=3.3.8.dev821851540", "mujoco-warp @ git+https://github.com/google-deepmind/mujoco_warp.git@bbd757cace561de47512b560517ee728c8416de5", # "newton @ git+https://github.com/newton-physics/newton.git@15b9955bafa61f8fcb40c17dc00f0b552d3c65ca", - "newton @ git+https://github.com/newton-physics/newton.git@c4baa06c3e8ea0a3090037b2b197e9aa453265f1", + "newton @ git+https://github.com/newton-physics/newton.git@1f115ae80579a01037adf519e62172a3b34c6ed7", "imgui-bundle==1.92.0", "PyOpenGL-accelerate==3.1.10", ] From a8c9d07ee73cf09a2d1da1895dd075622fe05ae9 Mon Sep 17 00:00:00 2001 From: mtrepte Date: Tue, 18 Nov 2025 23:57:05 -0800 Subject: [PATCH 11/24] wip --- source/isaaclab/isaaclab/sim/__init__.py | 1 - .../sim/scene_data_providers/__init__.py | 23 ----- .../newton_scene_data_provider.py | 87 ------------------- .../scene_data_provider.py | 84 ------------------ .../isaaclab/isaaclab/sim/simulation_cfg.py | 16 ++-- .../isaaclab/sim/simulation_context.py | 74 +++++++--------- .../sim/visualizers/newton_visualizer.py | 11 +-- .../isaaclab/sim/visualizers/ov_visualizer.py | 6 +- .../sim/visualizers/ov_visualizer_cfg.py | 8 +- .../sim/visualizers/rerun_visualizer.py | 25 ++---- .../isaaclab/sim/visualizers/visualizer.py | 11 ++- .../sim/visualizers/visualizer_cfg.py | 3 - source/isaaclab/setup.py | 4 +- 13 files changed, 67 insertions(+), 286 deletions(-) delete mode 100644 source/isaaclab/isaaclab/sim/scene_data_providers/__init__.py delete mode 100644 source/isaaclab/isaaclab/sim/scene_data_providers/newton_scene_data_provider.py delete mode 100644 source/isaaclab/isaaclab/sim/scene_data_providers/scene_data_provider.py diff --git a/source/isaaclab/isaaclab/sim/__init__.py b/source/isaaclab/isaaclab/sim/__init__.py index 7186730171c..ce3a3a16c24 100644 --- a/source/isaaclab/isaaclab/sim/__init__.py +++ b/source/isaaclab/isaaclab/sim/__init__.py @@ -27,7 +27,6 @@ """ from .converters import * # noqa: F401, F403 -from .scene_data_providers import NewtonSceneDataProvider, SceneDataProvider # noqa: F401, F403 from .schemas import * # noqa: F401, F403 from .simulation_cfg import RenderCfg, SimulationCfg # noqa: F401, F403 from .simulation_context import SimulationContext, build_simulation_context, enable_visualizers # noqa: F401, F403 diff --git a/source/isaaclab/isaaclab/sim/scene_data_providers/__init__.py b/source/isaaclab/isaaclab/sim/scene_data_providers/__init__.py deleted file mode 100644 index 6cb665547a4..00000000000 --- a/source/isaaclab/isaaclab/sim/scene_data_providers/__init__.py +++ /dev/null @@ -1,23 +0,0 @@ -# Copyright (c) 2022-2025, The Isaac Lab Project Developers. -# All rights reserved. -# -# SPDX-License-Identifier: BSD-3-Clause - -"""Sub-package for scene data provider implementations. - -This sub-package contains the abstract base class and concrete implementations -for providing scene data from various physics backends (Newton, PhysX, etc.) -to visualizers and renderers. - -The scene data provider abstraction allows visualizers and renderers to work -with any physics backend without directly coupling to specific backend implementations. -""" - -from .scene_data_provider import SceneDataProvider -from .newton_scene_data_provider import NewtonSceneDataProvider - -__all__ = [ - "SceneDataProvider", - "NewtonSceneDataProvider", -] - diff --git a/source/isaaclab/isaaclab/sim/scene_data_providers/newton_scene_data_provider.py b/source/isaaclab/isaaclab/sim/scene_data_providers/newton_scene_data_provider.py deleted file mode 100644 index 1966ba7a33b..00000000000 --- a/source/isaaclab/isaaclab/sim/scene_data_providers/newton_scene_data_provider.py +++ /dev/null @@ -1,87 +0,0 @@ -# Copyright (c) 2022-2025, The Isaac Lab Project Developers. -# All rights reserved. -# -# SPDX-License-Identifier: BSD-3-Clause - -"""Newton-specific scene data provider implementation.""" - -from __future__ import annotations - -from typing import TYPE_CHECKING, Any - -from .scene_data_provider import SceneDataProvider - -if TYPE_CHECKING: - from pxr import Usd - - -class NewtonSceneDataProvider(SceneDataProvider): - """Scene data provider for Newton physics backend. - - This class provides access to Newton physics data without directly exposing - the NewtonManager to downstream consumers. - """ - - def __init__(self, usd_stage: Usd.Stage | None = None): - """Initialize the Newton scene data provider. - - Args: - usd_stage: USD stage reference, if available. - """ - self._usd_stage = usd_stage - - def get_model(self) -> Any | None: - """Get the Newton physics model. - - Returns: - newton.Model instance, or None if not initialized. - """ - from isaaclab.sim._impl.newton_manager import NewtonManager - - return NewtonManager._model - - def get_state(self) -> Any | None: - """Get the current Newton physics state. - - Returns: - newton.State instance, or None if not initialized. - """ - from isaaclab.sim._impl.newton_manager import NewtonManager - - return NewtonManager._state_0 - - def get_usd_stage(self) -> Usd.Stage | None: - """Get the USD stage. - - Returns: - USD stage, or None if not available. - """ - return self._usd_stage - - def get_metadata(self) -> dict[str, Any]: - """Get Newton-specific metadata. - - Returns: - Dictionary containing: - - "physics_backend": "newton" - - "num_envs": int - - "gravity_vector": tuple[float, float, float] - - "clone_physics_only": bool - """ - from isaaclab.sim._impl.newton_manager import NewtonManager - - return { - "physics_backend": "newton", - "num_envs": NewtonManager._num_envs if NewtonManager._num_envs is not None else 0, - "gravity_vector": NewtonManager._gravity_vector, - "clone_physics_only": NewtonManager._clone_physics_only, - } - - def update_stage(self, usd_stage: Usd.Stage | None) -> None: - """Update the USD stage reference. - - Args: - usd_stage: New USD stage reference. - """ - self._usd_stage = usd_stage - diff --git a/source/isaaclab/isaaclab/sim/scene_data_providers/scene_data_provider.py b/source/isaaclab/isaaclab/sim/scene_data_providers/scene_data_provider.py deleted file mode 100644 index 2ab4c632e70..00000000000 --- a/source/isaaclab/isaaclab/sim/scene_data_providers/scene_data_provider.py +++ /dev/null @@ -1,84 +0,0 @@ -# Copyright (c) 2022-2025, The Isaac Lab Project Developers. -# All rights reserved. -# -# SPDX-License-Identifier: BSD-3-Clause - -"""Scene data provider abstraction for physics backends.""" - -from __future__ import annotations - -from abc import ABC, abstractmethod -from typing import TYPE_CHECKING, Any - -if TYPE_CHECKING: - from pxr import Usd - - -class SceneDataProvider(ABC): - """Abstract base class for providing scene data from physics backends to visualizers and renderers. - - This abstraction allows visualizers and renderers to work with any physics backend (Newton, PhysX, etc.) - without directly coupling to specific physics manager implementations. - """ - - @abstractmethod - def get_model(self) -> Any | None: - """Get the physics model. - - Returns: - Physics model object, or None if not available. The type depends on the backend - (e.g., newton.Model for Newton backend). - """ - pass - - @abstractmethod - def get_state(self) -> Any | None: - """Get the current physics state. - - Returns: - Physics state object, or None if not available. The type depends on the backend - (e.g., newton.State for Newton backend). - """ - pass - - @abstractmethod - def get_usd_stage(self) -> Usd.Stage | None: - """Get the USD stage. - - Returns: - USD stage, or None if not available. - """ - pass - - def get_metadata(self) -> dict[str, Any]: - """Get additional metadata about the scene. - - Returns: - Dictionary containing optional metadata such as: - - "physics_backend": str (e.g., "newton", "physx") - - "num_envs": int - - "device": str - - etc. - """ - return {} - - def get_scene_data(self) -> dict[str, Any]: - """Get all available scene data as a dictionary. - - This is a convenience method that collects all scene data into a single dict. - Individual visualizers can extract what they need. - - Returns: - Dictionary containing all available scene data: - - "model": Physics model - - "state": Physics state - - "usd_stage": USD stage - - "metadata": Additional metadata - """ - return { - "model": self.get_model(), - "state": self.get_state(), - "usd_stage": self.get_usd_stage(), - "metadata": self.get_metadata(), - } - diff --git a/source/isaaclab/isaaclab/sim/simulation_cfg.py b/source/isaaclab/isaaclab/sim/simulation_cfg.py index 22c13a60670..b6ad1c93f59 100644 --- a/source/isaaclab/isaaclab/sim/simulation_cfg.py +++ b/source/isaaclab/isaaclab/sim/simulation_cfg.py @@ -197,11 +197,8 @@ class SimulationCfg: render: RenderCfg = RenderCfg() """Render settings. Default is RenderCfg().""" - # visualizers: list[VisualizerCfg] | VisualizerCfg | None = NewtonVisualizerCfg(enabled=True) - visualizers: list[VisualizerCfg] | VisualizerCfg | None = OVVisualizerCfg(enabled=True) - # visualizers: list[VisualizerCfg] | VisualizerCfg | None = RerunVisualizerCfg(enabled=True) - # visualizers: list[VisualizerCfg] | VisualizerCfg | None = [NewtonVisualizerCfg(enabled=True), RerunVisualizerCfg(enabled=True)] - """Visualizer settings. Default is Newton (no visualizer). + visualizers: list[VisualizerCfg] | VisualizerCfg | None = None + """Visualizer settings. Default is None (no visualization). This field supports multiple visualizer backends for debug visualization and monitoring during simulation. It accepts: @@ -215,15 +212,18 @@ class SimulationCfg: - RerunVisualizerCfg: Web-based Rerun visualizer Examples: + # No visualizers (default) + cfg = SimulationCfg() + # Single visualizer from isaaclab.sim.visualizers import NewtonVisualizerCfg - cfg = SimulationCfg(visualizers=NewtonVisualizerCfg(enabled=True)) + cfg = SimulationCfg(visualizers=NewtonVisualizerCfg()) # Multiple visualizers from isaaclab.sim.visualizers import NewtonVisualizerCfg, RerunVisualizerCfg cfg = SimulationCfg(visualizers=[ - NewtonVisualizerCfg(enabled=True), - RerunVisualizerCfg(enabled=True) + NewtonVisualizerCfg(), + RerunVisualizerCfg() ]) Note: diff --git a/source/isaaclab/isaaclab/sim/simulation_context.py b/source/isaaclab/isaaclab/sim/simulation_context.py index 5eb886ba60c..6d0d6b0a5a9 100644 --- a/source/isaaclab/isaaclab/sim/simulation_context.py +++ b/source/isaaclab/isaaclab/sim/simulation_context.py @@ -30,7 +30,6 @@ from pxr import Usd from isaaclab.sim._impl.newton_manager import NewtonManager -from isaaclab.sim.scene_data_providers import NewtonSceneDataProvider, SceneDataProvider from isaaclab.sim.utils import create_new_stage_in_memory, use_stage from .simulation_cfg import SimulationCfg @@ -257,10 +256,6 @@ def __init__(self, cfg: SimulationCfg | None = None): # initialize visualizers self._visualizers: list[Visualizer] = [] self._visualizer_step_counter = 0 - - # Scene data provider for visualizers and renderers (initialized after stage is available) - self._scene_provider: SceneDataProvider | None = None - # flag for skipping prim deletion callback # when stage in memory is attached self._skip_next_prim_deletion_callback_fn = False @@ -304,9 +299,6 @@ def __init__(self, cfg: SimulationCfg | None = None): NewtonManager._clone_physics_only = ( self.render_mode == self.RenderMode.NO_GUI_OR_RENDERING or self.render_mode == self.RenderMode.NO_RENDERING ) - - # Initialize scene data provider now that stage is available - self._scene_provider = NewtonSceneDataProvider(self.stage) def _apply_physics_settings(self): """Sets various carb physics settings.""" @@ -563,28 +555,29 @@ def initialize_visualizers(self) -> None: visualizer_cfgs = [] if self.cfg.visualizers is not None: if isinstance(self.cfg.visualizers, list): - visualizer_cfgs = [cfg for cfg in self.cfg.visualizers if cfg.enabled] - elif self.cfg.visualizers.enabled: + visualizer_cfgs = self.cfg.visualizers + else: visualizer_cfgs = [self.cfg.visualizers] # Create and initialize each visualizer for viz_cfg in visualizer_cfgs: try: - # Use factory pattern to create visualizer from config visualizer = viz_cfg.create_visualizer() - # Get initial scene data from the scene provider - if self._scene_provider is None: - omni.log.warn( - f"Scene provider not initialized yet for visualizer '{viz_cfg.visualizer_type}'. " - "Visualizer will be initialized later." - ) - continue + # Prepare scene data from Newton physics backend + scene_data = { + "model": NewtonManager._model, + "state": NewtonManager._state_0, + "usd_stage": self.stage, + "metadata": { + "physics_backend": "newton", + "num_envs": NewtonManager._num_envs if NewtonManager._num_envs is not None else 0, + "gravity_vector": NewtonManager._gravity_vector, + "clone_physics_only": NewtonManager._clone_physics_only, + } + } - scene_data = self._scene_provider.get_scene_data() - - # Let each visualizer validate its own requirements - # (e.g., NewtonVisualizer needs Newton model, OVVisualizer needs USD stage) + # Initialize visualizer with scene data visualizer.initialize(scene_data) self._visualizers.append(visualizer) omni.log.info( @@ -624,15 +617,14 @@ def step_visualizers(self, dt: float) -> None: # Handle training pause - block until resumed while visualizer.is_training_paused() and visualizer.is_running(): - # Step with 0 dt during pause, pass scene provider for state updates - visualizer.step(0.0, self._scene_provider) + visualizer.step(0.0, state=NewtonManager._state_0) # Skip rendering if visualizer has rendering paused if visualizer.is_rendering_paused(): continue - # Normal step: pass dt and scene provider so visualizer can pull latest state - visualizer.step(dt, self._scene_provider) + # Normal step: pass updated Newton state + visualizer.step(dt, state=NewtonManager._state_0) except Exception as e: omni.log.error(f"Error stepping visualizer '{type(visualizer).__name__}': {e}") @@ -1033,29 +1025,25 @@ def build_simulation_context( def enable_visualizers(env_cfg, train_mode: bool = True) -> None: """Enable visualizers for an environment configuration. - If no visualizers are configured, defaults to Newton OpenGL visualizer. - If visualizers are already configured, enables them. - - This is a utility function for use in scripts that want to enable visualization - based on command-line arguments. + Sets visualizers to Newton OpenGL if none configured, and sets train_mode. Args: env_cfg: Environment configuration (DirectRLEnvCfg or ManagerBasedRLEnvCfg) to modify. train_mode: Whether to run visualizers in training mode (True) or play/inference mode (False). - Default is True. Example: >>> import isaaclab.sim as sim_utils >>> if args_cli.visualize: - ... sim_utils.enable_visualizers(env_cfg) # For training - ... sim_utils.enable_visualizers(env_cfg, train_mode=False) # For play/inference + ... sim_utils.enable_visualizers(env_cfg) """ - if env_cfg.sim.visualizers : - # Enable configured visualizer(s) - if isinstance(env_cfg.sim.visualizers, list): - for viz_cfg in env_cfg.sim.visualizers: - viz_cfg.enabled = True - viz_cfg.train_mode = train_mode - else: - env_cfg.sim.visualizers.enabled = True - env_cfg.sim.visualizers.train_mode = train_mode + from isaaclab.sim.visualizers import NewtonVisualizerCfg + + if env_cfg.sim.visualizers is None: + env_cfg.sim.visualizers = NewtonVisualizerCfg() + + # Set train_mode on all configured visualizers + if isinstance(env_cfg.sim.visualizers, list): + for viz_cfg in env_cfg.sim.visualizers: + viz_cfg.train_mode = train_mode + else: + env_cfg.sim.visualizers.train_mode = train_mode diff --git a/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py b/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py index 590b21b13dd..c434a27c432 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py +++ b/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py @@ -15,9 +15,6 @@ from .newton_visualizer_cfg import NewtonVisualizerCfg from .visualizer import Visualizer -if TYPE_CHECKING: - from isaaclab.sim.scene_data_providers import SceneDataProvider - class NewtonViewerGL(ViewerGL): """Training-aware viewer that adds a separate pause for simulation/training. @@ -311,7 +308,7 @@ def initialize(self, scene_data: dict[str, Any] | None = None) -> None: self._is_initialized = True - def step(self, dt: float, scene_provider: SceneDataProvider | None = None) -> None: + def step(self, dt: float, state: Any | None = None) -> None: """Update the visualizer for one simulation step. Note: The visualizer MUST be called every frame to maintain proper ImGui state. @@ -323,9 +320,9 @@ def step(self, dt: float, scene_provider: SceneDataProvider | None = None) -> No # Update simulation time self._sim_time += dt - # Get the latest state from the scene provider - if scene_provider is not None: - self._state = scene_provider.get_state() + # Update state if provided (state is passed directly from NewtonManager) + if state is not None: + self._state = state # Render the current frame (always call to maintain ImGui state) try: diff --git a/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer.py b/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer.py index 5163cfbe7d5..b7249770145 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer.py +++ b/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer.py @@ -11,8 +11,6 @@ import omni.log from typing import Any -from isaaclab.sim.scene_data_providers import SceneDataProvider - from .ov_visualizer_cfg import OVVisualizerCfg from .visualizer import Visualizer @@ -59,8 +57,8 @@ def initialize(self, scene_data: dict[str, Any] | None = None) -> None: self._is_initialized = True - def step(self, dt: float, scene_provider: SceneDataProvider | None = None) -> None: - """Update visualizer (rendering handled automatically by Isaac Sim).""" + def step(self, dt: float, state: Any | None = None) -> None: + """Update visualizer (no-op for OV - USD stage is auto-synced by Newton).""" if not self._is_initialized: return self._sim_time += dt diff --git a/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer_cfg.py b/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer_cfg.py index 40a57db5391..fe8f084fb1d 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer_cfg.py +++ b/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer_cfg.py @@ -21,19 +21,19 @@ class OVVisualizerCfg(VisualizerCfg): visualizer_type: str = "omniverse" """Type identifier for Omniverse visualizer.""" - viewport_name: str | None = "Visualizer" + viewport_name: str | None = "Visualizer Viewport" """Viewport name to use. If None, uses active viewport.""" - create_viewport: bool = True #False + create_viewport: bool = True """Create new viewport with specified name and camera pose.""" dock_position: str = "SAME" """Dock position for new viewport. Options: 'LEFT', 'RIGHT', 'BOTTOM', 'SAME' (tabs with existing).""" - window_width: int = 777 # 1920 + window_width: int = 1280 """Viewport width in pixels.""" - window_height: int = 777 # 1080 + window_height: int = 720 """Viewport height in pixels.""" camera_position: tuple[float, float, float] = (10.0, 10.0, 3.0) diff --git a/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer.py b/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer.py index a6438e76a38..338f45ba00e 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer.py +++ b/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer.py @@ -12,8 +12,6 @@ import torch from typing import Any -from isaaclab.sim.scene_data_providers import SceneDataProvider - from .rerun_visualizer_cfg import RerunVisualizerCfg from .visualizer import Visualizer @@ -60,9 +58,9 @@ def __init__( address=address, launch_viewer=launch_viewer, app_id=app_id, - # keep_historical_data=keep_historical_data, - # keep_scalar_history=keep_scalar_history, - # record_to_rrd=record_to_rrd, + keep_historical_data=keep_historical_data, + keep_scalar_history=keep_scalar_history, + record_to_rrd=record_to_rrd, ) # Isaac Lab state @@ -347,11 +345,11 @@ def initialize(self, scene_data: dict[str, Any] | None = None) -> None: omni.log.error(f"[RerunVisualizer] Failed to initialize viewer: {e}") raise - def step(self, dt: float, scene_provider: SceneDataProvider | None = None) -> None: + def step(self, dt: float, state: Any | None = None) -> None: """Update visualizer each step. This method: - 1. Updates state from scene provider (if available) + 1. Updates state (if provided) 2. Logs current state to Rerun (transforms, meshes) 3. Actively logs markers (if enabled) 4. Actively logs plot data (if enabled) @@ -360,23 +358,18 @@ def step(self, dt: float, scene_provider: SceneDataProvider | None = None) -> No Partial visualization (env_indices) is handled internally by filtering which instance transforms are logged. We log all meshes once (they're shared assets), but only log transforms for selected environments. - - Alternative implementations: - - Option A: Filter at the Newton state level (more invasive) - - Option B: Filter during logging (current - most flexible) - - Option C: Filter at the scene provider level (future consideration) Args: dt: Time step in seconds. - scene_provider: Optional scene data provider for updated state. + state: Updated physics state (e.g., newton.State). """ if not self._is_initialized or self._viewer is None: omni.log.warn("[RerunVisualizer] Not initialized. Call initialize() first.") return - # Update state from scene provider if available - if scene_provider is not None: - self._state = scene_provider.get_state() + # Update state if provided + if state is not None: + self._state = state # Begin frame self._viewer.begin_frame(self._sim_time) diff --git a/source/isaaclab/isaaclab/sim/visualizers/visualizer.py b/source/isaaclab/isaaclab/sim/visualizers/visualizer.py index 930cde03bcd..3ff45ef35df 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/visualizer.py +++ b/source/isaaclab/isaaclab/sim/visualizers/visualizer.py @@ -11,8 +11,6 @@ from typing import TYPE_CHECKING, Any if TYPE_CHECKING: - from isaaclab.sim.scene_data_providers import SceneDataProvider - from .visualizer_cfg import VisualizerCfg @@ -34,8 +32,13 @@ def initialize(self, scene_data: dict[str, Any] | None = None) -> None: pass @abstractmethod - def step(self, dt: float, scene_provider: SceneDataProvider | None = None) -> None: - """Update visualization for one step.""" + def step(self, dt: float, state: Any | None = None) -> None: + """Update visualization for one step. + + Args: + dt: Time step in seconds. + state: Updated physics state (e.g., newton.State). + """ pass @abstractmethod diff --git a/source/isaaclab/isaaclab/sim/visualizers/visualizer_cfg.py b/source/isaaclab/isaaclab/sim/visualizers/visualizer_cfg.py index afc618780c7..84668f05cca 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/visualizer_cfg.py +++ b/source/isaaclab/isaaclab/sim/visualizers/visualizer_cfg.py @@ -22,9 +22,6 @@ class VisualizerCfg: visualizer_type: str = "base" """Type identifier (e.g., 'newton', 'rerun', 'omniverse').""" - enabled: bool = False - """Whether the visualizer is enabled.""" - env_indices: list[int] | None = None """Environment indices to visualize. None = all environments.""" diff --git a/source/isaaclab/setup.py b/source/isaaclab/setup.py index 5421d4e6e85..82299d1ffc9 100644 --- a/source/isaaclab/setup.py +++ b/source/isaaclab/setup.py @@ -50,8 +50,8 @@ "usd-core==25.05.0", "mujoco>=3.3.8.dev821851540", "mujoco-warp @ git+https://github.com/google-deepmind/mujoco_warp.git@bbd757cace561de47512b560517ee728c8416de5", - # "newton @ git+https://github.com/newton-physics/newton.git@15b9955bafa61f8fcb40c17dc00f0b552d3c65ca", - "newton @ git+https://github.com/newton-physics/newton.git@1f115ae80579a01037adf519e62172a3b34c6ed7", + "newton @ git+https://github.com/newton-physics/newton.git@15b9955bafa61f8fcb40c17dc00f0b552d3c65ca", + # "newton @ git+https://github.com/newton-physics/newton.git@c4baa06c3e8ea0a3090037b2b197e9aa453265f1", "imgui-bundle==1.92.0", "PyOpenGL-accelerate==3.1.10", ] From 7ee435f30eb095e3e27ab237c539cddc58b9ebe1 Mon Sep 17 00:00:00 2001 From: mtrepte Date: Wed, 19 Nov 2025 01:05:32 -0800 Subject: [PATCH 12/24] adding feats --- scripts/demos/visualizers/demo_visualizers.py | 110 ++++++++ scripts/environments/random_agent.py | 4 +- scripts/environments/zero_agent.py | 4 +- .../reinforcement_learning/rl_games/play.py | 4 +- .../reinforcement_learning/rl_games/train.py | 4 +- scripts/reinforcement_learning/rsl_rl/play.py | 4 +- .../reinforcement_learning/rsl_rl/train.py | 4 +- scripts/reinforcement_learning/sb3/play.py | 4 +- scripts/reinforcement_learning/sb3/train.py | 4 +- scripts/reinforcement_learning/skrl/play.py | 4 +- scripts/reinforcement_learning/skrl/train.py | 4 +- scripts/sim2sim_transfer/rsl_rl_transfer.py | 4 +- .../isaaclab/isaaclab/sim/simulation_cfg.py | 9 +- .../isaaclab/sim/simulation_context.py | 30 +- .../sim/visualizers/newton_visualizer.py | 192 ++++++------- .../sim/visualizers/newton_visualizer_cfg.py | 53 +--- .../isaaclab/sim/visualizers/ov_visualizer.py | 55 +++- .../sim/visualizers/rerun_visualizer.py | 258 ++++++++++-------- .../sim/visualizers/rerun_visualizer_cfg.py | 4 +- .../sim/visualizers/visualizer_cfg.py | 4 +- 20 files changed, 442 insertions(+), 317 deletions(-) create mode 100644 scripts/demos/visualizers/demo_visualizers.py diff --git a/scripts/demos/visualizers/demo_visualizers.py b/scripts/demos/visualizers/demo_visualizers.py new file mode 100644 index 00000000000..2bd29af09ef --- /dev/null +++ b/scripts/demos/visualizers/demo_visualizers.py @@ -0,0 +1,110 @@ +#!/usr/bin/env python3 +# Copyright (c) 2022-2025, The Isaac Lab Project Developers. +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Quick demo script for testing different visualizer backends. + +Usage: + # Newton OpenGL (default) + python demo_visualizers.py --viz newton + + # Rerun web viewer + python demo_visualizers.py --viz rerun + + # Omniverse viewport + python demo_visualizers.py --viz ov + + # Multiple visualizers + python demo_visualizers.py --viz newton rerun + + # No visualizer + python demo_visualizers.py --viz none +""" + +import argparse +import torch + +import isaaclab.sim as sim_utils +from isaaclab.sim.visualizers import NewtonVisualizerCfg, OVVisualizerCfg, RerunVisualizerCfg +from isaaclab_tasks.utils.parse_cfg import parse_env_cfg + +# Simple CLI +parser = argparse.ArgumentParser(description="Visualizer Demo") +parser.add_argument("--task", type=str, default="Isaac-Cartpole-v0", help="Task name") +parser.add_argument("--num_envs", type=int, default=64, help="Number of environments") +parser.add_argument("--viz", nargs="+", default=["newton"], + choices=["newton", "rerun", "ov", "none"], + help="Visualizer(s) to use") +args = parser.parse_args() + +# Load env config +env_cfg = parse_env_cfg(args.task, device="cuda:0", num_envs=args.num_envs) + +# Setup visualizers based on CLI args +if "none" not in args.viz: + viz_cfgs = [] + + if "newton" in args.viz: + viz_cfgs.append(NewtonVisualizerCfg( + window_width=1280, + window_height=720, + camera_position=(10.0, 0.0, 3.0), + train_mode=True, + )) + + if "rerun" in args.viz: + viz_cfgs.append(RerunVisualizerCfg( + launch_viewer=True, + )) + + if "ov" in args.viz: + viz_cfgs.append(OVVisualizerCfg( + create_viewport=True, + viewport_name="Demo Viewport", + window_width=1280, + window_height=720, + camera_position=(10.0, 10.0, 3.0), + camera_target=(0.0, 0.0, 0.0), + )) + + # Set visualizers (single or list) + env_cfg.sim.visualizer_cfgs = viz_cfgs[0] if len(viz_cfgs) == 1 else viz_cfgs +else: + env_cfg.sim.visualizer_cfgs = None + +print(f"\n{'='*60}") +print(f"Visualizer Demo") +print(f"{'='*60}") +print(f"Task: {args.task}") +print(f"Num Envs: {args.num_envs}") +print(f"Visualizers: {args.viz}") +print(f"{'='*60}\n") + +# Create env +import gymnasium as gym +env = gym.make(args.task, cfg=env_cfg) + +# Quick test loop +print("Running simulation... (Ctrl+C to exit)") +env.reset() +step = 0 + +try: + while env.unwrapped.sim.is_playing(): + with torch.inference_mode(): + # Random actions + actions = 2 * torch.rand(env.action_space.shape, device=env.unwrapped.device) - 1 + obs, rew, terminated, truncated, info = env.step(actions) + + step += 1 + if step % 100 == 0: + print(f"Step {step} | Reward: {rew.mean().item():.3f}") + +except KeyboardInterrupt: + print("\nInterrupted by user") + +env.close() +print("Done!") + diff --git a/scripts/environments/random_agent.py b/scripts/environments/random_agent.py index dfb1302d3d5..865760b350b 100644 --- a/scripts/environments/random_agent.py +++ b/scripts/environments/random_agent.py @@ -19,7 +19,7 @@ parser.add_argument("--num_envs", type=int, default=None, help="Number of environments to simulate.") parser.add_argument("--task", type=str, default=None, help="Name of the task.") parser.add_argument( - "--visualize", + "--viz", action="store_true", default=False, help="Launch visualizer(s). Uses visualizers defined in environment config, or defaults to Newton OpenGL if none configured.", @@ -60,7 +60,7 @@ def main(): ) # enable visualizers if requested - if args_cli.visualize: + if args_cli.viz: import isaaclab.sim as sim_utils sim_utils.enable_visualizers(env_cfg) # create environment diff --git a/scripts/environments/zero_agent.py b/scripts/environments/zero_agent.py index 5b690c7caaf..fba99102a40 100644 --- a/scripts/environments/zero_agent.py +++ b/scripts/environments/zero_agent.py @@ -19,7 +19,7 @@ parser.add_argument("--num_envs", type=int, default=None, help="Number of environments to simulate.") parser.add_argument("--task", type=str, default=None, help="Name of the task.") parser.add_argument( - "--visualize", + "--viz", action="store_true", default=False, help="Launch visualizer(s). Uses visualizers defined in environment config, or defaults to Newton OpenGL if none configured.", @@ -60,7 +60,7 @@ def main(): ) # enable visualizers if requested - if args_cli.visualize: + if args_cli.viz: import isaaclab.sim as sim_utils sim_utils.enable_visualizers(env_cfg) # create environment diff --git a/scripts/reinforcement_learning/rl_games/play.py b/scripts/reinforcement_learning/rl_games/play.py index 189f89349e7..ff323874c62 100644 --- a/scripts/reinforcement_learning/rl_games/play.py +++ b/scripts/reinforcement_learning/rl_games/play.py @@ -33,7 +33,7 @@ ) parser.add_argument("--real-time", action="store_true", default=False, help="Run in real-time, if possible.") parser.add_argument( - "--visualize", + "--viz", action="store_true", default=False, help="Launch visualizer(s). Uses visualizers defined in environment config, or defaults to Newton OpenGL if none configured.", @@ -84,7 +84,7 @@ def main(): """Play with RL-Games agent.""" task_name = args_cli.task.split(":")[-1] # parse env configuration - env_cfg = parse_env_cfg(args_cli.task, device=args_cli.device, num_envs=args_cli.num_envs, use_fabric=not args_cli.disable_fabric, visualize=args_cli.visualize, train_mode=False) + env_cfg = parse_env_cfg(args_cli.task, device=args_cli.device, num_envs=args_cli.num_envs, use_fabric=not args_cli.disable_fabric, visualize=args_cli.viz, train_mode=False) agent_cfg = load_cfg_from_registry(args_cli.task, "rl_games_cfg_entry_point") # specify directory for logging experiments diff --git a/scripts/reinforcement_learning/rl_games/train.py b/scripts/reinforcement_learning/rl_games/train.py index 80a077eefa8..2eea3b3fbcb 100644 --- a/scripts/reinforcement_learning/rl_games/train.py +++ b/scripts/reinforcement_learning/rl_games/train.py @@ -39,7 +39,7 @@ help="if toggled, this experiment will be tracked with Weights and Biases", ) parser.add_argument( - "--visualize", + "--viz", action="store_true", default=False, help="Launch visualizer(s). Uses visualizers defined in environment config, or defaults to Newton OpenGL if none configured.", @@ -97,7 +97,7 @@ def main(env_cfg: ManagerBasedRLEnvCfg | DirectRLEnvCfg, agent_cfg: dict): env_cfg.sim.device = args_cli.device if args_cli.device is not None else env_cfg.sim.device # enable visualizers if requested - if args_cli.visualize: + if args_cli.viz: import isaaclab.sim as sim_utils sim_utils.enable_visualizers(env_cfg) diff --git a/scripts/reinforcement_learning/rsl_rl/play.py b/scripts/reinforcement_learning/rsl_rl/play.py index cf02ba60ea6..e7bd5c282a8 100644 --- a/scripts/reinforcement_learning/rsl_rl/play.py +++ b/scripts/reinforcement_learning/rsl_rl/play.py @@ -35,7 +35,7 @@ ) parser.add_argument("--real-time", action="store_true", default=False, help="Run in real-time, if possible.") parser.add_argument( - "--visualize", + "--viz", action="store_true", default=False, help="Launch visualizer(s). Uses visualizers defined in environment config, or defaults to Newton OpenGL if none configured.", @@ -103,7 +103,7 @@ def main(env_cfg: ManagerBasedRLEnvCfg | DirectRLEnvCfg, agent_cfg: RslRlBaseRun env_cfg.sim.device = args_cli.device if args_cli.device is not None else env_cfg.sim.device # enable visualizers if requested - if args_cli.visualize: + if args_cli.viz: import isaaclab.sim as sim_utils sim_utils.enable_visualizers(env_cfg, train_mode=False) diff --git a/scripts/reinforcement_learning/rsl_rl/train.py b/scripts/reinforcement_learning/rsl_rl/train.py index 380c1ae0b91..338919bcb4a 100644 --- a/scripts/reinforcement_learning/rsl_rl/train.py +++ b/scripts/reinforcement_learning/rsl_rl/train.py @@ -33,7 +33,7 @@ ) parser.add_argument("--export_io_descriptors", action="store_true", default=False, help="Export IO descriptors.") parser.add_argument( - "--visualize", + "--viz", action="store_true", default=False, help="Launch visualizer(s). Uses visualizers defined in environment config, or defaults to Newton OpenGL if none configured.", @@ -126,7 +126,7 @@ def main(env_cfg: ManagerBasedRLEnvCfg | DirectRLEnvCfg, agent_cfg: RslRlBaseRun env_cfg.sim.device = args_cli.device if args_cli.device is not None else env_cfg.sim.device # enable visualizers if requested - if args_cli.visualize: + if args_cli.viz: import isaaclab.sim as sim_utils sim_utils.enable_visualizers(env_cfg) diff --git a/scripts/reinforcement_learning/sb3/play.py b/scripts/reinforcement_learning/sb3/play.py index cb3473a29e3..6498bb4ca75 100644 --- a/scripts/reinforcement_learning/sb3/play.py +++ b/scripts/reinforcement_learning/sb3/play.py @@ -40,7 +40,7 @@ help="Use a slower SB3 wrapper but keep all the extra training info.", ) parser.add_argument( - "--visualize", + "--viz", action="store_true", default=False, help="Launch visualizer(s). Uses visualizers defined in environment config, or defaults to Newton OpenGL if none configured.", @@ -87,7 +87,7 @@ def main(): """Play with stable-baselines agent.""" # parse configuration - env_cfg = parse_env_cfg(args_cli.task, device=args_cli.device, num_envs=args_cli.num_envs, use_fabric=not args_cli.disable_fabric, visualize=args_cli.visualize, train_mode=False) + env_cfg = parse_env_cfg(args_cli.task, device=args_cli.device, num_envs=args_cli.num_envs, use_fabric=not args_cli.disable_fabric, visualize=args_cli.viz, train_mode=False) task_name = args_cli.task.split(":")[-1] train_task_name = task_name.replace("-Play", "") diff --git a/scripts/reinforcement_learning/sb3/train.py b/scripts/reinforcement_learning/sb3/train.py index 03ae5246269..f526c129f70 100644 --- a/scripts/reinforcement_learning/sb3/train.py +++ b/scripts/reinforcement_learning/sb3/train.py @@ -33,7 +33,7 @@ help="Use a slower SB3 wrapper but keep all the extra training info.", ) parser.add_argument( - "--visualize", + "--viz", action="store_true", default=False, help="Launch visualizer(s). Uses visualizers defined in environment config, or defaults to Newton OpenGL if none configured.", @@ -120,7 +120,7 @@ def main(env_cfg: ManagerBasedRLEnvCfg | DirectRLEnvCfg, agent_cfg: dict): env_cfg.sim.device = args_cli.device if args_cli.device is not None else env_cfg.sim.device # enable visualizers if requested - if args_cli.visualize: + if args_cli.viz: import isaaclab.sim as sim_utils sim_utils.enable_visualizers(env_cfg) diff --git a/scripts/reinforcement_learning/skrl/play.py b/scripts/reinforcement_learning/skrl/play.py index 54b93ec97f4..e0b9670b284 100644 --- a/scripts/reinforcement_learning/skrl/play.py +++ b/scripts/reinforcement_learning/skrl/play.py @@ -47,7 +47,7 @@ ) parser.add_argument("--real-time", action="store_true", default=False, help="Run in real-time, if possible.") parser.add_argument( - "--visualize", + "--viz", action="store_true", default=False, help="Launch visualizer(s). Uses visualizers defined in environment config, or defaults to Newton OpenGL if none configured.", @@ -116,7 +116,7 @@ def main(): task_name = args_cli.task.split(":")[-1] # parse configuration - env_cfg = parse_env_cfg(args_cli.task, device=args_cli.device, num_envs=args_cli.num_envs, use_fabric=not args_cli.disable_fabric, visualize=args_cli.visualize, train_mode=False) + env_cfg = parse_env_cfg(args_cli.task, device=args_cli.device, num_envs=args_cli.num_envs, use_fabric=not args_cli.disable_fabric, visualize=args_cli.viz, train_mode=False) try: experiment_cfg = load_cfg_from_registry(task_name, f"skrl_{algorithm}_cfg_entry_point") except ValueError: diff --git a/scripts/reinforcement_learning/skrl/train.py b/scripts/reinforcement_learning/skrl/train.py index add4686603f..158a6b8292d 100644 --- a/scripts/reinforcement_learning/skrl/train.py +++ b/scripts/reinforcement_learning/skrl/train.py @@ -45,7 +45,7 @@ help="The RL algorithm used for training the skrl agent.", ) parser.add_argument( - "--visualize", + "--viz", action="store_true", default=False, help="Launch visualizer(s). Uses visualizers defined in environment config, or defaults to Newton OpenGL if none configured.", @@ -120,7 +120,7 @@ def main(env_cfg: ManagerBasedRLEnvCfg | DirectRLEnvCfg, agent_cfg: dict): env_cfg.sim.device = args_cli.device if args_cli.device is not None else env_cfg.sim.device # enable visualizers if requested - if args_cli.visualize: + if args_cli.viz: import isaaclab.sim as sim_utils sim_utils.enable_visualizers(env_cfg) diff --git a/scripts/sim2sim_transfer/rsl_rl_transfer.py b/scripts/sim2sim_transfer/rsl_rl_transfer.py index 63f92c2e3e7..218e595366b 100644 --- a/scripts/sim2sim_transfer/rsl_rl_transfer.py +++ b/scripts/sim2sim_transfer/rsl_rl_transfer.py @@ -30,7 +30,7 @@ ) parser.add_argument("--real-time", action="store_true", default=False, help="Run in real-time, if possible.") parser.add_argument( - "--visualize", + "--viz", action="store_true", default=False, help="Launch visualizer(s). Uses visualizers defined in environment config, or defaults to Newton OpenGL if none configured.", @@ -155,7 +155,7 @@ def main(): ) # enable visualizers if requested - if args_cli.visualize: + if args_cli.viz: import isaaclab.sim as sim_utils sim_utils.enable_visualizers(env_cfg) agent_cfg: RslRlOnPolicyRunnerCfg = cli_args.parse_rsl_rl_cfg(task_name, args_cli) diff --git a/source/isaaclab/isaaclab/sim/simulation_cfg.py b/source/isaaclab/isaaclab/sim/simulation_cfg.py index b6ad1c93f59..dbb98360844 100644 --- a/source/isaaclab/isaaclab/sim/simulation_cfg.py +++ b/source/isaaclab/isaaclab/sim/simulation_cfg.py @@ -194,10 +194,11 @@ class SimulationCfg: The material is created at the path: ``{physics_prim_path}/defaultMaterial``. """ - render: RenderCfg = RenderCfg() + render_cfg: RenderCfg = RenderCfg() """Render settings. Default is RenderCfg().""" - visualizers: list[VisualizerCfg] | VisualizerCfg | None = None + # visualizer_cfgs: list[VisualizerCfg] | VisualizerCfg | None = None + visualizer_cfgs: list[VisualizerCfg] | VisualizerCfg | None = NewtonVisualizerCfg(env_ids_to_viz=[0]) """Visualizer settings. Default is None (no visualization). This field supports multiple visualizer backends for debug visualization and monitoring @@ -217,11 +218,11 @@ class SimulationCfg: # Single visualizer from isaaclab.sim.visualizers import NewtonVisualizerCfg - cfg = SimulationCfg(visualizers=NewtonVisualizerCfg()) + cfg = SimulationCfg(visualizer_cfgs=NewtonVisualizerCfg()) # Multiple visualizers from isaaclab.sim.visualizers import NewtonVisualizerCfg, RerunVisualizerCfg - cfg = SimulationCfg(visualizers=[ + cfg = SimulationCfg(visualizer_cfgs=[ NewtonVisualizerCfg(), RerunVisualizerCfg() ]) diff --git a/source/isaaclab/isaaclab/sim/simulation_context.py b/source/isaaclab/isaaclab/sim/simulation_context.py index 6d0d6b0a5a9..45b470e7efe 100644 --- a/source/isaaclab/isaaclab/sim/simulation_context.py +++ b/source/isaaclab/isaaclab/sim/simulation_context.py @@ -326,7 +326,7 @@ def _apply_render_settings_from_cfg(self): not_carb_settings = ["rendering_mode", "carb_settings", "antialiasing_mode"] # set preset settings (same behavior as the CLI arg --rendering_mode) - rendering_mode = self.cfg.render.rendering_mode + rendering_mode = self.cfg.render_cfg.rendering_mode if rendering_mode is not None: # check if preset is supported supported_rendering_modes = ["performance", "balanced", "quality"] @@ -348,7 +348,7 @@ def _apply_render_settings_from_cfg(self): set_carb_setting(self.carb_settings, key, value) # set user-friendly named settings - for key, value in vars(self.cfg.render).items(): + for key, value in vars(self.cfg.render_cfg).items(): if value is None or key in not_carb_settings: # skip unset settings and non-carb settings continue @@ -361,7 +361,7 @@ def _apply_render_settings_from_cfg(self): set_carb_setting(self.carb_settings, key, value) # set general carb settings - carb_settings = self.cfg.render.carb_settings + carb_settings = self.cfg.render_cfg.carb_settings if carb_settings is not None: for key, value in carb_settings.items(): if "_" in key: @@ -373,11 +373,11 @@ def _apply_render_settings_from_cfg(self): set_carb_setting(self.carb_settings, key, value) # set denoiser mode - if self.cfg.render.antialiasing_mode is not None: + if self.cfg.render_cfg.antialiasing_mode is not None: try: import omni.replicator.core as rep - rep.settings.set_render_rtx_realtime(antialiasing=self.cfg.render.antialiasing_mode) + rep.settings.set_render_rtx_realtime(antialiasing=self.cfg.render_cfg.antialiasing_mode) except Exception: pass @@ -546,18 +546,18 @@ def initialize_visualizers(self) -> None: """Initialize all configured visualizers. This method creates and initializes visualizers based on the configuration provided - in SimulationCfg.visualizers. It supports: + in SimulationCfg.visualizer_cfgs. It supports: - A single VisualizerCfg: Creates one visualizer - A list of VisualizerCfg: Creates multiple visualizers - None or empty list: No visualizers are created """ # Handle different input formats visualizer_cfgs = [] - if self.cfg.visualizers is not None: - if isinstance(self.cfg.visualizers, list): - visualizer_cfgs = self.cfg.visualizers + if self.cfg.visualizer_cfgs is not None: + if isinstance(self.cfg.visualizer_cfgs, list): + visualizer_cfgs = self.cfg.visualizer_cfgs else: - visualizer_cfgs = [self.cfg.visualizers] + visualizer_cfgs = [self.cfg.visualizer_cfgs] # Create and initialize each visualizer for viz_cfg in visualizer_cfgs: @@ -1038,12 +1038,12 @@ def enable_visualizers(env_cfg, train_mode: bool = True) -> None: """ from isaaclab.sim.visualizers import NewtonVisualizerCfg - if env_cfg.sim.visualizers is None: - env_cfg.sim.visualizers = NewtonVisualizerCfg() + if env_cfg.sim.visualizer_cfgs is None: + env_cfg.sim.visualizer_cfgs = NewtonVisualizerCfg() # Set train_mode on all configured visualizers - if isinstance(env_cfg.sim.visualizers, list): - for viz_cfg in env_cfg.sim.visualizers: + if isinstance(env_cfg.sim.visualizer_cfgs, list): + for viz_cfg in env_cfg.sim.visualizer_cfgs: viz_cfg.train_mode = train_mode else: - env_cfg.sim.visualizers.train_mode = train_mode + env_cfg.sim.visualizer_cfgs.train_mode = train_mode diff --git a/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py b/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py index c434a27c432..fa166197767 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py +++ b/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py @@ -17,21 +17,20 @@ class NewtonViewerGL(ViewerGL): - """Training-aware viewer that adds a separate pause for simulation/training. + """Wrapper around Newton's ViewerGL with training/rendering pause controls. - This class subclasses Newton's ViewerGL and introduces a second pause mode: - - Rendering pause: identical to the base viewer's pause (space key / Pause checkbox) - - Training pause: stops simulation/training steps but keeps rendering running - - The training pause can be toggled from the UI via a button and optionally via the 'T' key. + Adds two pause modes: + - Training pause: Stops physics simulation, continues rendering + - Rendering pause: Stops rendering updates, continues physics (SPACE key) """ - def __init__(self, *args, metadata: dict | None = None, **kwargs): + def __init__(self, *args, train_mode: bool = True, metadata: dict | None = None, **kwargs): super().__init__(*args, **kwargs) - self._paused_training: bool = False - self._paused_rendering: bool = False - self._fallback_draw_controls: bool = False + self._paused_training = False + self._paused_rendering = False + self._is_train_mode = train_mode self._metadata = metadata or {} + self._fallback_draw_controls = False try: self.register_ui_callback(self._render_training_controls, position="side") @@ -39,27 +38,34 @@ def __init__(self, *args, metadata: dict | None = None, **kwargs): self._fallback_draw_controls = True def is_training_paused(self) -> bool: - """Check if training is paused.""" return self._paused_training def is_rendering_paused(self) -> bool: - """Check if rendering is paused.""" + return self._paused_rendering + + def is_paused(self) -> bool: + # duplicate to above for now return self._paused_rendering - # UI callback rendered inside the "Example Options" panel of the left sidebar def _render_training_controls(self, imgui): imgui.separator() - imgui.text("Isaac Lab Training Controls") - pause_label = "Resume Training" if self._paused_training else "Pause Training" + if self._is_train_mode: + imgui.text("IsaacLab Training Controls") + pause_label = "Resume Training" if self._paused_training else "Pause Training" + else: + imgui.text("IsaacLab Playback Controls") + pause_label = "Resume Playing" if self._paused_training else "Pause Playing" + if imgui.button(pause_label): self._paused_training = not self._paused_training - rendering_label = "Resume Rendering" if self._paused_rendering else "Pause Rendering" - if imgui.button(rendering_label): - self._paused_rendering = not self._paused_rendering + if self._is_train_mode: + rendering_label = "Resume Rendering" if self._paused_rendering else "Pause Rendering" + if imgui.button(rendering_label): + self._paused_rendering = not self._paused_rendering + self._paused = self._paused_rendering - # Override only SPACE key to use rendering pause, preserve all other shortcuts def on_key_press(self, symbol, modifiers): if self.ui.is_capturing(): return @@ -70,11 +76,10 @@ def on_key_press(self, symbol, modifiers): return if symbol == pyglet.window.key.SPACE: - # Override SPACE to pause rendering instead of base pause self._paused_rendering = not self._paused_rendering + self._paused = self._paused_rendering return - # For all other keys, call base implementation to preserve functionality super().on_key_press(symbol, modifiers) def _render_ui(self): @@ -215,69 +220,49 @@ def _render_left_panel(self): class NewtonVisualizer(Visualizer): - """Newton OpenGL Visualizer for Isaac Lab. - - This visualizer uses Newton's OpenGL-based viewer to provide lightweight, - fast visualization of simulations. It includes IsaacLab-specific features - like training controls, rendering pause, and update frequency adjustment. - - This class is registered with the visualizer registry as "newton" and can be - instantiated via NewtonVisualizerCfg.create_visualizer(). + """Newton OpenGL visualizer for Isaac Lab. - Args: - cfg: Configuration for the Newton visualizer. + Lightweight OpenGL-based visualization with training/rendering pause controls. """ def __init__(self, cfg: NewtonVisualizerCfg): super().__init__(cfg) self.cfg: NewtonVisualizerCfg = cfg self._viewer: NewtonViewerGL | None = None - self._sim_time: float = 0.0 - self._step_counter: int = 0 + self._sim_time = 0.0 + self._step_counter = 0 self._model = None self._state = None def initialize(self, scene_data: dict[str, Any] | None = None) -> None: - """Initialize the Newton visualizer with the simulation scene. - - Args: - scene_data: Optional dictionary containing initial scene data. Expected keys: - - "model": Newton Model object (required) - - "state": Newton State object (optional) - - "metadata": Scene metadata (contains physics_backend) - - Raises: - RuntimeError: If Newton model is not available or if physics backend is incompatible. - """ + """Initialize visualizer with scene data.""" if self._is_initialized: return - # Extract model, state, and metadata from scene data metadata = {} if scene_data is not None: self._model = scene_data.get("model") self._state = scene_data.get("state") metadata = scene_data.get("metadata", {}) - # Validate physics backend compatibility physics_backend = metadata.get("physics_backend", "unknown") if physics_backend != "newton" and physics_backend != "unknown": raise RuntimeError( - f"Newton visualizer requires Newton physics backend, but '{physics_backend}' is running. " - f"Please use a compatible visualizer for {physics_backend} physics (e.g., OVVisualizer)." + f"Newton visualizer requires Newton physics backend, got '{physics_backend}'. " + f"Use OVVisualizer for other backends." ) - # Validate required data if self._model is None: raise RuntimeError( - "Newton visualizer requires a Newton Model in scene_data['model']. " - "Make sure Newton physics is initialized before creating the visualizer." + "Newton visualizer requires Newton Model in scene_data['model']. " + "Ensure Newton physics is initialized first." ) - # Create the viewer with metadata + # Create the viewer with train_mode and metadata self._viewer = NewtonViewerGL( width=self.cfg.window_width, height=self.cfg.window_height, + train_mode=self.cfg.train_mode, metadata=metadata, ) @@ -306,110 +291,91 @@ def initialize(self, scene_data: dict[str, Any] | None = None) -> None: self._viewer.renderer.sky_lower = self.cfg.ground_color self._viewer.renderer._light_color = self.cfg.light_color + # Setup partial visualization (env_ids_to_viz filtering) + if self.cfg.env_ids_to_viz is not None: + num_envs = metadata.get("num_envs", 0) + self._setup_env_filtering(num_envs) + omni.log.info( + f"[NewtonVisualizer] Partial visualization: {len(self.cfg.env_ids_to_viz)}/{num_envs} environments" + ) + self._is_initialized = True def step(self, dt: float, state: Any | None = None) -> None: - """Update the visualizer for one simulation step. - - Note: The visualizer MUST be called every frame to maintain proper ImGui state. - Pause handling (training and rendering) is managed by SimulationContext. - """ + """Update visualizer for one step.""" if not self._is_initialized or self._is_closed or self._viewer is None: return - # Update simulation time self._sim_time += dt - - # Update state if provided (state is passed directly from NewtonManager) if state is not None: self._state = state - # Render the current frame (always call to maintain ImGui state) try: - self._viewer.begin_frame(self._sim_time) - try: + if not self._viewer.is_paused(): + self._viewer.begin_frame(self._sim_time) if self._state is not None: self._viewer.log_state(self._state) - finally: - # Always call end_frame if begin_frame succeeded self._viewer.end_frame() - except Exception as e: - # Handle any rendering errors gracefully - # Frame lifecycle is now properly handled by try-finally - pass # Silently ignore to avoid log spam - the viewer will recover + else: + self._viewer._update() + except Exception: + pass def close(self) -> None: - """Close the visualizer and clean up resources.""" + """Close visualizer and clean up resources.""" if self._is_closed: return - if self._viewer is not None: - try: - # Newton viewer doesn't have an explicit close method, - # but we can clean up our reference - self._viewer = None - except Exception as e: - print(f"[Warning] Error closing Newton visualizer: {e}") - + self._viewer = None self._is_closed = True def is_running(self) -> bool: - """Check if the visualizer is still running. - - Returns: - True if the visualizer window is open and running. - """ + """Check if visualizer window is still open.""" if not self._is_initialized or self._is_closed or self._viewer is None: return False - return self._viewer.is_running() def supports_markers(self) -> bool: - """Check if Newton visualizer supports visualization markers. - - Returns: - False - Newton visualizer currently does not support VisualizationMarkers - (they are USD-based and Newton uses its own rendering). - """ + """Newton visualizer does not support USD-based markers.""" return False def supports_live_plots(self) -> bool: - """Check if Newton visualizer supports live plots. - - Returns: - True - Newton visualizer supports live plots via ImGui integration. - """ + """Newton visualizer supports ImGui-based plots.""" return True def is_training_paused(self) -> bool: - """Check if training is paused by the visualizer. - - Returns: - True if the user has paused training via the visualizer controls. - """ + """Check if training is paused.""" if not self._is_initialized or self._viewer is None: return False - return self._viewer.is_training_paused() def is_rendering_paused(self) -> bool: - """Check if rendering is paused by the visualizer. - - Returns: - True if rendering is paused via the visualizer controls. - """ + """Check if rendering is paused.""" if not self._is_initialized or self._viewer is None: return False - return self._viewer.is_rendering_paused() - - def update_state(self, state) -> None: - """Update the simulation state for visualization. + + def _setup_env_filtering(self, num_envs: int) -> None: + """Setup environment filtering using world offsets. - This method should be called before step() to provide the latest simulation state. + WIP: Moves non-visualized environments far away (10000 units) to hide them. + Future: Could use more sophisticated filtering or culling. Args: - state: The Newton State object to visualize. + num_envs: Total number of environments. """ - self._state = state + import warp as wp + + # Create world offsets array + offsets = wp.zeros(num_envs, dtype=wp.vec3, device=self._viewer.renderer.device) + offsets_np = offsets.numpy() + + # Move non-visualized environments far away + visualized_set = set(self.cfg.env_ids_to_viz) + for world_idx in range(num_envs): + if world_idx not in visualized_set: + offsets_np[world_idx] = (10000.0, 10000.0, 10000.0) + + offsets.assign(offsets_np) + self._viewer.world_offsets = offsets diff --git a/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer_cfg.py b/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer_cfg.py index eeca2a53736..f604e3c7ea8 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer_cfg.py +++ b/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer_cfg.py @@ -37,24 +37,23 @@ class NewtonVisualizerCfg(VisualizerCfg): camera_target: tuple[float, float, float] = (0.0, 0.0, 0.0) """Initial camera target/look-at point (x, y, z).""" - # Newton-specific settings - fps: int = 60 - """Target FPS.""" + train_mode: bool = True + """Training mode (True) shows rendering pause controls, play mode (False) hides them.""" - show_joints: bool = True - """Show joint visualizations.""" + up_axis: Literal["X", "Y", "Z"] = "Z" + """World up axis.""" + + show_joints: bool = False + """Show joint visualization.""" show_contacts: bool = False - """Show contact visualizations.""" + """Show contact visualization.""" show_springs: bool = False - """Show spring visualizations.""" + """Show spring visualization.""" show_com: bool = False - """Show center of mass visualizations.""" - - show_ui: bool = True - """Show UI sidebar (toggle with 'H' key).""" + """Show center of mass visualization.""" enable_shadows: bool = True """Enable shadow rendering.""" @@ -63,39 +62,15 @@ class NewtonVisualizerCfg(VisualizerCfg): """Enable sky rendering.""" enable_wireframe: bool = False - """Enable wireframe rendering mode.""" - - up_axis: Literal["X", "Y", "Z"] = "Z" - """Up axis for visualizer (should match simulation).""" - - fov: float = 60.0 - """Camera field of view in degrees.""" - - near_plane: float = 0.1 - """Camera near clipping plane distance.""" - - far_plane: float = 1000.0 - """Camera far clipping plane distance.""" + """Enable wireframe rendering.""" background_color: tuple[float, float, float] = (0.53, 0.81, 0.92) - """Background/sky color RGB [0,1] (light blue).""" + """Background/sky color RGB [0,1].""" ground_color: tuple[float, float, float] = (0.18, 0.20, 0.25) - """Ground color RGB [0,1] (dark gray).""" + """Ground color RGB [0,1].""" light_color: tuple[float, float, float] = (1.0, 1.0, 1.0) - """Light color RGB [0,1] (white).""" - - enable_pause_training: bool = True - """Enable pause training button in UI.""" - - enable_pause_rendering: bool = True - """Enable pause rendering button in UI.""" - - show_training_controls: bool = True - """Show Isaac Lab training controls in UI.""" - - render_mode: Literal["rgb", "depth", "collision"] = "rgb" - """Rendering mode: rgb (standard), depth, or collision.""" + """Light color RGB [0,1].""" diff --git a/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer.py b/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer.py index b7249770145..a7f4a69c72f 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer.py +++ b/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer.py @@ -51,9 +51,14 @@ def initialize(self, scene_data: dict[str, Any] | None = None) -> None: self._ensure_simulation_app() self._setup_viewport(usd_stage, metadata) - physics_backend = metadata.get("physics_backend", "unknown") + # Setup partial visualization (env_ids_to_viz filtering) num_envs = metadata.get("num_envs", 0) - omni.log.info(f"[OVVisualizer] Initialized ({num_envs} envs, {physics_backend} physics)") + if self.cfg.env_ids_to_viz is not None: + self._setup_env_filtering(usd_stage, metadata, num_envs) + + physics_backend = metadata.get("physics_backend", "unknown") + viz_envs = len(self.cfg.env_ids_to_viz) if self.cfg.env_ids_to_viz else num_envs + omni.log.info(f"[OVVisualizer] Initialized ({viz_envs}/{num_envs} envs, {physics_backend} physics)") self._is_initialized = True @@ -86,10 +91,12 @@ def is_training_paused(self) -> bool: return False def supports_markers(self) -> bool: + # Should we add marker configuration, or let the env itself handle it. """Supports markers via USD prims.""" return True def supports_live_plots(self) -> bool: + # Should we automatically focus the live plots window? """Supports live plots via Isaac Lab UI.""" return True @@ -336,3 +343,47 @@ def _set_viewport_camera( except Exception as e: omni.log.warn(f"[OVVisualizer] Could not set camera: {e}") + + def _setup_env_filtering(self, usd_stage, metadata: dict, num_envs: int) -> None: + """Setup environment filtering by hiding non-visualized environment prims. + + WIP: Sets USD visibility to 'invisible' for non-visualized environments. + Future: Could use more sophisticated culling or instancing techniques. + + Args: + usd_stage: The USD stage. + metadata: Scene metadata containing environment prim paths. + num_envs: Total number of environments. + """ + try: + from pxr import UsdGeom + + # Get environment prim pattern from metadata + # Default pattern assumes envs are at /World/envs/env_* + env_prim_pattern = metadata.get("env_prim_pattern", "/World/envs/env_{}") + + visualized_set = set(self.cfg.env_ids_to_viz) + hidden_count = 0 + + for env_idx in range(num_envs): + if env_idx not in visualized_set: + # Format the environment prim path + env_path = env_prim_pattern.format(env_idx) + prim = usd_stage.GetPrimAtPath(env_path) + + if prim.IsValid(): + # Make the prim invisible + imageable = UsdGeom.Imageable(prim) + if imageable: + imageable.MakeInvisible() + hidden_count += 1 + else: + omni.log.warn(f"[OVVisualizer] Environment prim not found: {env_path}") + + omni.log.info( + f"[OVVisualizer] Partial visualization enabled: " + f"hidden {hidden_count} environments, showing {len(self.cfg.env_ids_to_viz)}/{num_envs}" + ) + + except Exception as e: + omni.log.warn(f"[OVVisualizer] Failed to setup environment filtering: {e}") diff --git a/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer.py b/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer.py index 338f45ba00e..6071b1445f5 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer.py +++ b/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer.py @@ -46,7 +46,7 @@ def __init__( metadata: dict | None = None, enable_markers: bool = True, enable_live_plots: bool = True, - env_indices: list[int] | None = None, + env_ids_to_viz: list[int] | None = None, ): """Initialize Newton ViewerRerun wrapper.""" if not _RERUN_AVAILABLE: @@ -58,16 +58,16 @@ def __init__( address=address, launch_viewer=launch_viewer, app_id=app_id, - keep_historical_data=keep_historical_data, - keep_scalar_history=keep_scalar_history, - record_to_rrd=record_to_rrd, + # keep_historical_data=keep_historical_data, + # keep_scalar_history=keep_scalar_history, + # record_to_rrd=record_to_rrd, ) # Isaac Lab state self._metadata = metadata or {} self._enable_markers = enable_markers self._enable_live_plots = enable_live_plots - self._env_indices = env_indices + self._env_ids_to_viz = env_ids_to_viz # Storage for registered markers and plots self._registered_markers = [] @@ -88,8 +88,8 @@ def _log_metadata(self) -> None: num_envs = self._metadata.get("num_envs", 0) metadata_text += f"**Total Environments:** {num_envs}\n" - if self._env_indices is not None: - metadata_text += f"**Visualized Environments:** {len(self._env_indices)} (indices: {self._env_indices[:5]}...)\n" + if self._env_ids_to_viz is not None: + metadata_text += f"**Visualized Environments:** {len(self._env_ids_to_viz)} (IDs: {self._env_ids_to_viz[:5]}...)\n" else: metadata_text += f"**Visualized Environments:** All ({num_envs})\n" @@ -130,127 +130,122 @@ def register_plots(self, plots: dict[str, Any]) -> None: omni.log.info(f"[RerunVisualizer] Registered {len(plots)} plot(s)") def log_markers(self) -> None: - """Actively log all registered VisualizationMarkers to Rerun. + """Log registered VisualizationMarkers to Rerun. - This method converts Isaac Lab's USD-based markers to Rerun entities. - - Supported marker types: - - Arrows: Logged as line segments via rr.LineStrips3D - - Frames: Logged as XYZ axes via rr.LineStrips3D (3 lines per frame) - - Spheres: Logged as points via rr.Points3D with radii - - Implementation Strategy: - We convert USD-based visualization markers to Rerun primitives. - Since markers are scene-managed and updated by their owners, - we need to extract their current state each frame and log it. - - TODO: Future enhancements - - Support more marker types (cylinders, cones, boxes) - - Optimize batch logging for large marker counts - - Add color/material support for better visual distinction + Converts Isaac Lab markers to Rerun primitives (arrows, frames, spheres). """ if not self._enable_markers or len(self._registered_markers) == 0: return try: for marker_idx, markers in enumerate(self._registered_markers): - # Extract marker data - # Note: This is a simplified implementation that assumes markers - # expose their data through specific methods/properties. - # Actual implementation depends on VisualizationMarkers API. + # Check if markers object has data access methods + if not hasattr(markers, 'data'): + continue - # For now, we'll use Newton's built-in logging methods - # which VisualizationMarkers should be compatible with + marker_data = markers.data + entity_path = f"markers/{markers.__class__.__name__}_{marker_idx}" - # TODO: Implement proper marker extraction and conversion - # marker_data = markers.get_marker_data() - # self._log_marker_data(marker_data, f"markers/{marker_idx}") + # Log arrows as line segments + if hasattr(marker_data, 'arrows') and marker_data.arrows is not None: + arrows = marker_data.arrows + if hasattr(arrows, 'positions') and hasattr(arrows, 'directions'): + positions = arrows.positions.cpu().numpy() if hasattr(arrows.positions, 'cpu') else arrows.positions + directions = arrows.directions.cpu().numpy() if hasattr(arrows.directions, 'cpu') else arrows.directions + + if len(positions) > 0: + # Create line segments from position to position+direction + for i in range(len(positions)): + start = positions[i] + end = start + directions[i] + rr.log(f"{entity_path}/arrow_{i}", rr.Arrows3D( + origins=[start], + vectors=[directions[i]] + )) - pass # Stub for now + # Log spheres as 3D points with radii + if hasattr(marker_data, 'spheres') and marker_data.spheres is not None: + spheres = marker_data.spheres + if hasattr(spheres, 'positions'): + positions = spheres.positions.cpu().numpy() if hasattr(spheres.positions, 'cpu') else spheres.positions + radii = spheres.radii.cpu().numpy() if hasattr(spheres, 'radii') else [0.05] * len(positions) + + if len(positions) > 0: + rr.log(f"{entity_path}/spheres", rr.Points3D( + positions=positions, + radii=radii + )) + + # Log coordinate frames as transform axes + if hasattr(marker_data, 'frames') and marker_data.frames is not None: + frames = marker_data.frames + if hasattr(frames, 'positions') and hasattr(frames, 'orientations'): + positions = frames.positions.cpu().numpy() if hasattr(frames.positions, 'cpu') else frames.positions + orientations = frames.orientations.cpu().numpy() if hasattr(frames.orientations, 'cpu') else frames.orientations + scale = frames.scale if hasattr(frames, 'scale') else 0.1 + + for i in range(len(positions)): + # Log as transform with axes + rr.log(f"{entity_path}/frame_{i}", rr.Transform3D( + translation=positions[i], + rotation=rr.Quaternion(xyzw=orientations[i]), + axis_length=scale + )) except Exception as e: omni.log.warn(f"[RerunVisualizer] Failed to log markers: {e}") def log_plot_data(self) -> None: - """Actively log all registered LivePlot data to Rerun as time series. - - This method extracts scalar data from LivePlot objects and logs them - as Rerun Scalars, enabling visualization alongside the 3D scene. - - Implementation Strategy: - LivePlots in Isaac Lab are typically omni.ui-based widgets that - display time-series data. For Rerun, we need to extract the raw - scalar values and log them using rr.Scalar(). - - TODO: Full implementation - - Extract data from LiveLinePlot objects - - Handle multiple series per plot - - Maintain proper timeline synchronization - - Support different plot types (line, bar, etc.) - """ + """Log registered LivePlot data to Rerun as time series scalars.""" if not self._enable_live_plots or len(self._registered_plots) == 0: return try: for plot_name, plot_obj in self._registered_plots.items(): - # TODO: Extract data from plot object - # For now, this is a stub - # data = plot_obj.get_latest_data() - # rr.log(f"plots/{plot_name}", rr.Scalar(data)) + # Try to extract data from common plot object attributes + data_value = None + + # Method 1: Check for 'value' or 'data' attribute + if hasattr(plot_obj, 'value'): + data_value = plot_obj.value + elif hasattr(plot_obj, 'data'): + data_value = plot_obj.data + + # Method 2: Check for get_data() or get_value() methods + elif hasattr(plot_obj, 'get_data'): + data_value = plot_obj.get_data() + elif hasattr(plot_obj, 'get_value'): + data_value = plot_obj.get_value() - pass # Stub for now + # Method 3: Check for buffer/history attribute (get latest value) + elif hasattr(plot_obj, 'buffer') and plot_obj.buffer is not None: + if len(plot_obj.buffer) > 0: + data_value = plot_obj.buffer[-1] + elif hasattr(plot_obj, 'history') and plot_obj.history is not None: + if len(plot_obj.history) > 0: + data_value = plot_obj.history[-1] + + # Log the scalar value if we found it + if data_value is not None: + # Convert tensor to scalar if needed + if hasattr(data_value, 'item'): + data_value = data_value.item() + elif hasattr(data_value, 'cpu'): + data_value = data_value.cpu().numpy() + + # Handle numpy arrays (take mean if multi-dimensional) + if isinstance(data_value, np.ndarray): + if data_value.size == 1: + data_value = float(data_value.flat[0]) + else: + data_value = float(np.mean(data_value)) + + # Log as scalar + rr.log(f"plots/{plot_name}", rr.Scalar(float(data_value))) except Exception as e: omni.log.warn(f"[RerunVisualizer] Failed to log plot data: {e}") - def _log_marker_data(self, marker_data: dict, entity_path: str) -> None: - """Helper to log specific marker data to Rerun. - - Args: - marker_data: Dictionary containing marker positions, types, colors, etc. - entity_path: Rerun entity path for logging. - """ - marker_type = marker_data.get("type", "unknown") - - if marker_type == "arrow": - # Log arrows as line segments - starts = marker_data.get("positions") # Start points - directions = marker_data.get("directions") # Direction vectors - - if starts is not None and directions is not None: - ends = starts + directions - self.log_lines( - entity_path, - starts=starts, - ends=ends, - colors=marker_data.get("colors"), - width=marker_data.get("width", 0.01), - ) - - elif marker_type == "frame": - # Log coordinate frames as 3 lines (XYZ axes) - positions = marker_data.get("positions") - orientations = marker_data.get("orientations") - scale = marker_data.get("scale", 0.1) - - if positions is not None and orientations is not None: - # TODO: Convert quaternions to XYZ axis lines - # For each frame, create 3 lines (red=X, green=Y, blue=Z) - pass - - elif marker_type == "sphere": - # Log spheres as points with radii - positions = marker_data.get("positions") - radii = marker_data.get("radii", 0.05) - colors = marker_data.get("colors") - - if positions is not None: - self.log_points( - entity_path, - points=positions, - radii=radii, - colors=colors, - ) class RerunVisualizer(Visualizer): @@ -325,15 +320,19 @@ def initialize(self, scene_data: dict[str, Any] | None = None) -> None: metadata=metadata, enable_markers=self.cfg.enable_markers, enable_live_plots=self.cfg.enable_live_plots, - env_indices=self.cfg.env_indices, + env_ids_to_viz=self.cfg.env_ids_to_viz, ) # Set the model self._viewer.set_model(self._model) - # Log initialization + # Setup partial visualization (env_ids_to_viz filtering) num_envs = metadata.get("num_envs", 0) - viz_envs = len(self.cfg.env_indices) if self.cfg.env_indices else num_envs + if self.cfg.env_ids_to_viz is not None: + self._setup_env_filtering(num_envs) + + # Log initialization + viz_envs = len(self.cfg.env_ids_to_viz) if self.cfg.env_ids_to_viz else num_envs omni.log.info( f"[RerunVisualizer] Initialized with {viz_envs}/{num_envs} environments " f"(physics: {physics_backend})" @@ -355,7 +354,7 @@ def step(self, dt: float, state: Any | None = None) -> None: 4. Actively logs plot data (if enabled) Implementation Note: - Partial visualization (env_indices) is handled internally by filtering + Partial visualization (env_ids_to_viz) is handled internally by filtering which instance transforms are logged. We log all meshes once (they're shared assets), but only log transforms for selected environments. @@ -371,18 +370,15 @@ def step(self, dt: float, state: Any | None = None) -> None: if state is not None: self._state = state - # Begin frame + # Update internal time + self._sim_time += dt + + # Begin frame with current simulation time self._viewer.begin_frame(self._sim_time) # Log state (transforms) - Newton's ViewerRerun handles this if self._state is not None: - # Handle partial visualization if env_indices is set - if self.cfg.env_indices is not None: - # TODO: Filter state to only visualized environments - # For now, log all state (Newton's ViewerRerun will handle it) - self._viewer.log_state(self._state) - else: - self._viewer.log_state(self._state) + self._viewer.log_state(self._state) # Actively log markers (if enabled) if self.cfg.enable_markers: @@ -394,9 +390,6 @@ def step(self, dt: float, state: Any | None = None) -> None: # End frame self._viewer.end_frame() - - # Update internal time - self._sim_time += dt def close(self) -> None: """Clean up Rerun visualizer resources and finalize recordings.""" @@ -476,4 +469,33 @@ def register_plots(self, plots: dict[str, Any]) -> None: """ if self._viewer: self._viewer.register_plots(plots) + + def _setup_env_filtering(self, num_envs: int) -> None: + """Setup environment filtering using world offsets. + + WIP: Moves non-visualized environments far away (10000 units) to hide them. + Future: Could implement proper state filtering before logging. + + Args: + num_envs: Total number of environments. + """ + import warp as wp + + # Create world offsets array + offsets = wp.zeros(num_envs, dtype=wp.vec3, device=self._viewer.device) + offsets_np = offsets.numpy() + + # Move non-visualized environments far away + visualized_set = set(self.cfg.env_ids_to_viz) + for world_idx in range(num_envs): + if world_idx not in visualized_set: + offsets_np[world_idx] = (10000.0, 10000.0, 10000.0) + + offsets.assign(offsets_np) + self._viewer.world_offsets = offsets + + omni.log.info( + f"[RerunVisualizer] Partial visualization enabled: " + f"{len(self.cfg.env_ids_to_viz)}/{num_envs} environments" + ) diff --git a/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer_cfg.py b/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer_cfg.py index f722ee4a746..aacae6aa3a6 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer_cfg.py +++ b/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer_cfg.py @@ -35,12 +35,12 @@ class RerunVisualizerCfg(VisualizerCfg): app_id: str = "isaaclab-simulation" """Application identifier shown in viewer title.""" - keep_historical_data: bool = True + keep_historical_data: bool = False """Keep transform history for time scrubbing (False = constant memory for training).""" keep_scalar_history: bool = True """Keep scalar/plot history in timeline.""" - record_to_rrd: str | None = "/tmp/test.rrd" + record_to_rrd: str | None = None """Path to save .rrd recording file. None = no recording.""" diff --git a/source/isaaclab/isaaclab/sim/visualizers/visualizer_cfg.py b/source/isaaclab/isaaclab/sim/visualizers/visualizer_cfg.py index 84668f05cca..abdc7ecc5e6 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/visualizer_cfg.py +++ b/source/isaaclab/isaaclab/sim/visualizers/visualizer_cfg.py @@ -22,8 +22,8 @@ class VisualizerCfg: visualizer_type: str = "base" """Type identifier (e.g., 'newton', 'rerun', 'omniverse').""" - env_indices: list[int] | None = None - """Environment indices to visualize. None = all environments.""" + env_ids_to_viz: list[int] | None = None + """Environment IDs to visualize. None = all environments.""" enable_markers: bool = True """Enable visualization markers (debug drawing).""" From 011c373c1ffaaeb7a1bf240bd189548a3dd9b092 Mon Sep 17 00:00:00 2001 From: mtrepte Date: Wed, 19 Nov 2025 01:22:13 -0800 Subject: [PATCH 13/24] wip --- scripts/environments/random_agent.py | 7 +- scripts/environments/zero_agent.py | 7 +- .../reinforcement_learning/rl_games/play.py | 7 +- .../reinforcement_learning/rl_games/train.py | 7 +- scripts/reinforcement_learning/rsl_rl/play.py | 7 +- .../reinforcement_learning/rsl_rl/train.py | 7 +- scripts/reinforcement_learning/sb3/play.py | 7 +- scripts/reinforcement_learning/sb3/train.py | 7 +- scripts/reinforcement_learning/skrl/play.py | 7 +- scripts/reinforcement_learning/skrl/train.py | 7 +- scripts/sim2sim_transfer/rsl_rl_transfer.py | 7 +- .../isaaclab/isaaclab/sim/simulation_cfg.py | 2 +- .../isaaclab/sim/visualizers/__init__.py | 96 ++++++++++--------- .../sim/visualizers/newton_visualizer.py | 5 +- 14 files changed, 65 insertions(+), 115 deletions(-) diff --git a/scripts/environments/random_agent.py b/scripts/environments/random_agent.py index 865760b350b..0a4acd72062 100644 --- a/scripts/environments/random_agent.py +++ b/scripts/environments/random_agent.py @@ -18,12 +18,7 @@ ) parser.add_argument("--num_envs", type=int, default=None, help="Number of environments to simulate.") parser.add_argument("--task", type=str, default=None, help="Name of the task.") -parser.add_argument( - "--viz", - action="store_true", - default=False, - help="Launch visualizer(s). Uses visualizers defined in environment config, or defaults to Newton OpenGL if none configured.", -) +parser.add_argument("--viz", action="store_true", default=False, help="Enable visualization.") # append AppLauncher cli args AppLauncher.add_app_launcher_args(parser) # parse the arguments diff --git a/scripts/environments/zero_agent.py b/scripts/environments/zero_agent.py index fba99102a40..ca5c74d8ce7 100644 --- a/scripts/environments/zero_agent.py +++ b/scripts/environments/zero_agent.py @@ -18,12 +18,7 @@ ) parser.add_argument("--num_envs", type=int, default=None, help="Number of environments to simulate.") parser.add_argument("--task", type=str, default=None, help="Name of the task.") -parser.add_argument( - "--viz", - action="store_true", - default=False, - help="Launch visualizer(s). Uses visualizers defined in environment config, or defaults to Newton OpenGL if none configured.", -) +parser.add_argument("--viz", action="store_true", default=False, help="Enable visualization.") # append AppLauncher cli args AppLauncher.add_app_launcher_args(parser) # parse the arguments diff --git a/scripts/reinforcement_learning/rl_games/play.py b/scripts/reinforcement_learning/rl_games/play.py index ff323874c62..f1c57f160b8 100644 --- a/scripts/reinforcement_learning/rl_games/play.py +++ b/scripts/reinforcement_learning/rl_games/play.py @@ -32,12 +32,7 @@ help="When no checkpoint provided, use the last saved model. Otherwise use the best saved model.", ) parser.add_argument("--real-time", action="store_true", default=False, help="Run in real-time, if possible.") -parser.add_argument( - "--viz", - action="store_true", - default=False, - help="Launch visualizer(s). Uses visualizers defined in environment config, or defaults to Newton OpenGL if none configured.", -) +parser.add_argument("--viz", action="store_true", default=False, help="Enable visualization.") # append AppLauncher cli args AppLauncher.add_app_launcher_args(parser) # parse the arguments diff --git a/scripts/reinforcement_learning/rl_games/train.py b/scripts/reinforcement_learning/rl_games/train.py index 2eea3b3fbcb..8376498045a 100644 --- a/scripts/reinforcement_learning/rl_games/train.py +++ b/scripts/reinforcement_learning/rl_games/train.py @@ -38,12 +38,7 @@ const=True, help="if toggled, this experiment will be tracked with Weights and Biases", ) -parser.add_argument( - "--viz", - action="store_true", - default=False, - help="Launch visualizer(s). Uses visualizers defined in environment config, or defaults to Newton OpenGL if none configured.", -) +parser.add_argument("--viz", action="store_true", default=False, help="Enable visualization.") # append AppLauncher cli args AppLauncher.add_app_launcher_args(parser) # parse the arguments diff --git a/scripts/reinforcement_learning/rsl_rl/play.py b/scripts/reinforcement_learning/rsl_rl/play.py index e7bd5c282a8..233eab273d7 100644 --- a/scripts/reinforcement_learning/rsl_rl/play.py +++ b/scripts/reinforcement_learning/rsl_rl/play.py @@ -34,12 +34,7 @@ help="Use the pre-trained checkpoint from Nucleus.", ) parser.add_argument("--real-time", action="store_true", default=False, help="Run in real-time, if possible.") -parser.add_argument( - "--viz", - action="store_true", - default=False, - help="Launch visualizer(s). Uses visualizers defined in environment config, or defaults to Newton OpenGL if none configured.", -) +parser.add_argument("--viz", action="store_true", default=False, help="Enable visualization.") # append RSL-RL cli arguments cli_args.add_rsl_rl_args(parser) # append AppLauncher cli args diff --git a/scripts/reinforcement_learning/rsl_rl/train.py b/scripts/reinforcement_learning/rsl_rl/train.py index 338919bcb4a..9a77fd31e80 100644 --- a/scripts/reinforcement_learning/rsl_rl/train.py +++ b/scripts/reinforcement_learning/rsl_rl/train.py @@ -32,12 +32,7 @@ "--distributed", action="store_true", default=False, help="Run training with multiple GPUs or nodes." ) parser.add_argument("--export_io_descriptors", action="store_true", default=False, help="Export IO descriptors.") -parser.add_argument( - "--viz", - action="store_true", - default=False, - help="Launch visualizer(s). Uses visualizers defined in environment config, or defaults to Newton OpenGL if none configured.", -) +parser.add_argument("--viz", action="store_true", default=False, help="Enable visualization.") # append RSL-RL cli arguments cli_args.add_rsl_rl_args(parser) # append AppLauncher cli args diff --git a/scripts/reinforcement_learning/sb3/play.py b/scripts/reinforcement_learning/sb3/play.py index 6498bb4ca75..ec9ba0714cb 100644 --- a/scripts/reinforcement_learning/sb3/play.py +++ b/scripts/reinforcement_learning/sb3/play.py @@ -39,12 +39,7 @@ default=False, help="Use a slower SB3 wrapper but keep all the extra training info.", ) -parser.add_argument( - "--viz", - action="store_true", - default=False, - help="Launch visualizer(s). Uses visualizers defined in environment config, or defaults to Newton OpenGL if none configured.", -) +parser.add_argument("--viz", action="store_true", default=False, help="Enable visualization.") # append AppLauncher cli args AppLauncher.add_app_launcher_args(parser) # parse the arguments diff --git a/scripts/reinforcement_learning/sb3/train.py b/scripts/reinforcement_learning/sb3/train.py index f526c129f70..d96b1a5af6e 100644 --- a/scripts/reinforcement_learning/sb3/train.py +++ b/scripts/reinforcement_learning/sb3/train.py @@ -32,12 +32,7 @@ default=False, help="Use a slower SB3 wrapper but keep all the extra training info.", ) -parser.add_argument( - "--viz", - action="store_true", - default=False, - help="Launch visualizer(s). Uses visualizers defined in environment config, or defaults to Newton OpenGL if none configured.", -) +parser.add_argument("--viz", action="store_true", default=False, help="Enable visualization.") # append AppLauncher cli args AppLauncher.add_app_launcher_args(parser) # parse the arguments diff --git a/scripts/reinforcement_learning/skrl/play.py b/scripts/reinforcement_learning/skrl/play.py index e0b9670b284..d6103b2cc53 100644 --- a/scripts/reinforcement_learning/skrl/play.py +++ b/scripts/reinforcement_learning/skrl/play.py @@ -46,12 +46,7 @@ help="The RL algorithm used for training the skrl agent.", ) parser.add_argument("--real-time", action="store_true", default=False, help="Run in real-time, if possible.") -parser.add_argument( - "--viz", - action="store_true", - default=False, - help="Launch visualizer(s). Uses visualizers defined in environment config, or defaults to Newton OpenGL if none configured.", -) +parser.add_argument("--viz", action="store_true", default=False, help="Enable visualization.") # append AppLauncher cli args AppLauncher.add_app_launcher_args(parser) diff --git a/scripts/reinforcement_learning/skrl/train.py b/scripts/reinforcement_learning/skrl/train.py index 158a6b8292d..e8474545a24 100644 --- a/scripts/reinforcement_learning/skrl/train.py +++ b/scripts/reinforcement_learning/skrl/train.py @@ -44,12 +44,7 @@ choices=["AMP", "PPO", "IPPO", "MAPPO"], help="The RL algorithm used for training the skrl agent.", ) -parser.add_argument( - "--viz", - action="store_true", - default=False, - help="Launch visualizer(s). Uses visualizers defined in environment config, or defaults to Newton OpenGL if none configured.", -) +parser.add_argument("--viz", action="store_true", default=False, help="Enable visualization.") # append AppLauncher cli args AppLauncher.add_app_launcher_args(parser) diff --git a/scripts/sim2sim_transfer/rsl_rl_transfer.py b/scripts/sim2sim_transfer/rsl_rl_transfer.py index 218e595366b..168abb8356b 100644 --- a/scripts/sim2sim_transfer/rsl_rl_transfer.py +++ b/scripts/sim2sim_transfer/rsl_rl_transfer.py @@ -29,12 +29,7 @@ help="Use the pre-trained checkpoint from Nucleus.", ) parser.add_argument("--real-time", action="store_true", default=False, help="Run in real-time, if possible.") -parser.add_argument( - "--viz", - action="store_true", - default=False, - help="Launch visualizer(s). Uses visualizers defined in environment config, or defaults to Newton OpenGL if none configured.", -) +parser.add_argument("--viz", action="store_true", default=False, help="Enable visualization.") # Joint ordering arguments parser.add_argument( "--policy_transfer_file", diff --git a/source/isaaclab/isaaclab/sim/simulation_cfg.py b/source/isaaclab/isaaclab/sim/simulation_cfg.py index dbb98360844..c9dc1c89f9b 100644 --- a/source/isaaclab/isaaclab/sim/simulation_cfg.py +++ b/source/isaaclab/isaaclab/sim/simulation_cfg.py @@ -198,7 +198,7 @@ class SimulationCfg: """Render settings. Default is RenderCfg().""" # visualizer_cfgs: list[VisualizerCfg] | VisualizerCfg | None = None - visualizer_cfgs: list[VisualizerCfg] | VisualizerCfg | None = NewtonVisualizerCfg(env_ids_to_viz=[0]) + visualizer_cfgs: list[VisualizerCfg] | VisualizerCfg | None = OVVisualizerCfg(env_ids_to_viz=[0]) """Visualizer settings. Default is None (no visualization). This field supports multiple visualizer backends for debug visualization and monitoring diff --git a/source/isaaclab/isaaclab/sim/visualizers/__init__.py b/source/isaaclab/isaaclab/sim/visualizers/__init__.py index 271897c1030..1abc058258c 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/__init__.py +++ b/source/isaaclab/isaaclab/sim/visualizers/__init__.py @@ -25,9 +25,6 @@ from typing import TYPE_CHECKING, Any -if TYPE_CHECKING: - from typing import Type - # Import base classes first from .visualizer import Visualizer from .visualizer_cfg import VisualizerCfg @@ -37,67 +34,74 @@ from .ov_visualizer_cfg import OVVisualizerCfg from .rerun_visualizer_cfg import RerunVisualizerCfg -# Import visualizer implementations -from .newton_visualizer import NewtonVisualizer -from .ov_visualizer import OVVisualizer -from .rerun_visualizer import RerunVisualizer +# NOTE: Visualizer implementations are NOT imported here to avoid loading +# dependencies for unused visualizers (REQ-10: clean dependency handling). +# They are lazy-loaded via the registry when actually needed. + +if TYPE_CHECKING: + from typing import Type + from .newton_visualizer import NewtonVisualizer + from .ov_visualizer import OVVisualizer + from .rerun_visualizer import RerunVisualizer -# Global registry for visualizer types (defined after Visualizer import) +# Global registry for visualizer types (lazy-loaded) _VISUALIZER_REGISTRY: dict[str, Any] = {} __all__ = [ "Visualizer", "VisualizerCfg", - "NewtonVisualizer", "NewtonVisualizerCfg", - "OVVisualizer", "OVVisualizerCfg", - "RerunVisualizer", "RerunVisualizerCfg", - "register_visualizer", "get_visualizer_class", ] - -def register_visualizer(name: str): - """Decorator to register a visualizer class with the given name. - - This allows visualizer configs to create instances without hard-coded type checking. - - Args: - name: Unique identifier for this visualizer type (e.g., "newton", "rerun", "omniverse"). - - Example: - >>> @register_visualizer("newton") - >>> class NewtonVisualizer(Visualizer): - >>> pass - """ - - def decorator(cls: Type[Visualizer]) -> Type[Visualizer]: - if name in _VISUALIZER_REGISTRY: - raise ValueError(f"Visualizer '{name}' is already registered!") - _VISUALIZER_REGISTRY[name] = cls - return cls - - return decorator +# Note: Visualizer implementation classes (NewtonVisualizer, OVVisualizer, RerunVisualizer) +# are not exported to avoid eager loading. Access them via get_visualizer_class() or +# VisualizerCfg.create_visualizer() instead. def get_visualizer_class(name: str) -> Type[Visualizer] | None: - """Get a registered visualizer class by name. + """Get a visualizer class by name (lazy-loaded). + + Visualizer classes are imported only when requested to avoid loading + unnecessary dependencies (REQ-10: clean dependency handling). Args: - name: Visualizer type name. + name: Visualizer type name (e.g., 'newton', 'rerun', 'omniverse', 'ov'). Returns: - Visualizer class, or None if not found. + Visualizer class if found, None otherwise. + + Example: + >>> visualizer_cls = get_visualizer_class('newton') + >>> if visualizer_cls: + >>> visualizer = visualizer_cls(cfg) """ - return _VISUALIZER_REGISTRY.get(name) - - -# Register built-in visualizers -# Note: Registration happens here to avoid circular imports -_VISUALIZER_REGISTRY["newton"] = NewtonVisualizer -_VISUALIZER_REGISTRY["omniverse"] = OVVisualizer -_VISUALIZER_REGISTRY["ov"] = OVVisualizer # Alias for convenience -_VISUALIZER_REGISTRY["rerun"] = RerunVisualizer + # Check if already loaded + if name in _VISUALIZER_REGISTRY: + return _VISUALIZER_REGISTRY[name] + + # Lazy-load visualizer on first access + try: + if name == "newton": + from .newton_visualizer import NewtonVisualizer + _VISUALIZER_REGISTRY["newton"] = NewtonVisualizer + return NewtonVisualizer + elif name in ("omniverse", "ov"): + from .ov_visualizer import OVVisualizer + _VISUALIZER_REGISTRY["omniverse"] = OVVisualizer + _VISUALIZER_REGISTRY["ov"] = OVVisualizer # Alias + return OVVisualizer + elif name == "rerun": + from .rerun_visualizer import RerunVisualizer + _VISUALIZER_REGISTRY["rerun"] = RerunVisualizer + return RerunVisualizer + else: + return None + except ImportError as e: + # Log import error but don't crash - visualizer just won't be available + import warnings + warnings.warn(f"Failed to load visualizer '{name}': {e}", ImportWarning) + return None diff --git a/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py b/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py index fa166197767..30d41f96cd7 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py +++ b/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py @@ -9,6 +9,7 @@ from typing import TYPE_CHECKING, Any +import omni.log import warp as wp from newton.viewer import ViewerGL @@ -366,8 +367,8 @@ def _setup_env_filtering(self, num_envs: int) -> None: """ import warp as wp - # Create world offsets array - offsets = wp.zeros(num_envs, dtype=wp.vec3, device=self._viewer.renderer.device) + # Create world offsets array (use viewer's device, not renderer's) + offsets = wp.zeros(num_envs, dtype=wp.vec3, device=self._viewer.device) offsets_np = offsets.numpy() # Move non-visualized environments far away From c0a3b1ea07c2228f2c5ee53b85ec570589de28ce Mon Sep 17 00:00:00 2001 From: mtrepte Date: Wed, 19 Nov 2025 11:10:34 -0800 Subject: [PATCH 14/24] cleaning up --- scripts/demos/visualizers/demo_visualizers.py | 110 ------------------ scripts/environments/random_agent.py | 11 +- scripts/environments/zero_agent.py | 11 +- .../reinforcement_learning/rl_games/play.py | 2 +- .../reinforcement_learning/rl_games/train.py | 11 +- scripts/reinforcement_learning/rsl_rl/play.py | 17 ++- .../reinforcement_learning/rsl_rl/train.py | 11 +- scripts/reinforcement_learning/sb3/play.py | 2 +- scripts/reinforcement_learning/sb3/train.py | 11 +- scripts/reinforcement_learning/skrl/play.py | 2 +- scripts/reinforcement_learning/skrl/train.py | 11 +- scripts/sim2sim_transfer/rsl_rl_transfer.py | 11 +- .../isaaclab/isaaclab/sim/simulation_cfg.py | 25 ++-- .../isaaclab/sim/visualizers/__init__.py | 14 +-- .../sim/visualizers/newton_visualizer.py | 26 ++++- .../sim/visualizers/newton_visualizer_cfg.py | 3 + .../sim/visualizers/rerun_visualizer.py | 2 + 17 files changed, 104 insertions(+), 176 deletions(-) delete mode 100644 scripts/demos/visualizers/demo_visualizers.py diff --git a/scripts/demos/visualizers/demo_visualizers.py b/scripts/demos/visualizers/demo_visualizers.py deleted file mode 100644 index 2bd29af09ef..00000000000 --- a/scripts/demos/visualizers/demo_visualizers.py +++ /dev/null @@ -1,110 +0,0 @@ -#!/usr/bin/env python3 -# Copyright (c) 2022-2025, The Isaac Lab Project Developers. -# All rights reserved. -# -# SPDX-License-Identifier: BSD-3-Clause - -"""Quick demo script for testing different visualizer backends. - -Usage: - # Newton OpenGL (default) - python demo_visualizers.py --viz newton - - # Rerun web viewer - python demo_visualizers.py --viz rerun - - # Omniverse viewport - python demo_visualizers.py --viz ov - - # Multiple visualizers - python demo_visualizers.py --viz newton rerun - - # No visualizer - python demo_visualizers.py --viz none -""" - -import argparse -import torch - -import isaaclab.sim as sim_utils -from isaaclab.sim.visualizers import NewtonVisualizerCfg, OVVisualizerCfg, RerunVisualizerCfg -from isaaclab_tasks.utils.parse_cfg import parse_env_cfg - -# Simple CLI -parser = argparse.ArgumentParser(description="Visualizer Demo") -parser.add_argument("--task", type=str, default="Isaac-Cartpole-v0", help="Task name") -parser.add_argument("--num_envs", type=int, default=64, help="Number of environments") -parser.add_argument("--viz", nargs="+", default=["newton"], - choices=["newton", "rerun", "ov", "none"], - help="Visualizer(s) to use") -args = parser.parse_args() - -# Load env config -env_cfg = parse_env_cfg(args.task, device="cuda:0", num_envs=args.num_envs) - -# Setup visualizers based on CLI args -if "none" not in args.viz: - viz_cfgs = [] - - if "newton" in args.viz: - viz_cfgs.append(NewtonVisualizerCfg( - window_width=1280, - window_height=720, - camera_position=(10.0, 0.0, 3.0), - train_mode=True, - )) - - if "rerun" in args.viz: - viz_cfgs.append(RerunVisualizerCfg( - launch_viewer=True, - )) - - if "ov" in args.viz: - viz_cfgs.append(OVVisualizerCfg( - create_viewport=True, - viewport_name="Demo Viewport", - window_width=1280, - window_height=720, - camera_position=(10.0, 10.0, 3.0), - camera_target=(0.0, 0.0, 0.0), - )) - - # Set visualizers (single or list) - env_cfg.sim.visualizer_cfgs = viz_cfgs[0] if len(viz_cfgs) == 1 else viz_cfgs -else: - env_cfg.sim.visualizer_cfgs = None - -print(f"\n{'='*60}") -print(f"Visualizer Demo") -print(f"{'='*60}") -print(f"Task: {args.task}") -print(f"Num Envs: {args.num_envs}") -print(f"Visualizers: {args.viz}") -print(f"{'='*60}\n") - -# Create env -import gymnasium as gym -env = gym.make(args.task, cfg=env_cfg) - -# Quick test loop -print("Running simulation... (Ctrl+C to exit)") -env.reset() -step = 0 - -try: - while env.unwrapped.sim.is_playing(): - with torch.inference_mode(): - # Random actions - actions = 2 * torch.rand(env.action_space.shape, device=env.unwrapped.device) - 1 - obs, rew, terminated, truncated, info = env.step(actions) - - step += 1 - if step % 100 == 0: - print(f"Step {step} | Reward: {rew.mean().item():.3f}") - -except KeyboardInterrupt: - print("\nInterrupted by user") - -env.close() -print("Done!") - diff --git a/scripts/environments/random_agent.py b/scripts/environments/random_agent.py index 0a4acd72062..2676710c2bb 100644 --- a/scripts/environments/random_agent.py +++ b/scripts/environments/random_agent.py @@ -18,7 +18,7 @@ ) parser.add_argument("--num_envs", type=int, default=None, help="Number of environments to simulate.") parser.add_argument("--task", type=str, default=None, help="Name of the task.") -parser.add_argument("--viz", action="store_true", default=False, help="Enable visualization.") +parser.add_argument("--viz", action="store_true", default=False, help="Enable visualization for monitoring and debugging.") # append AppLauncher cli args AppLauncher.add_app_launcher_args(parser) # parse the arguments @@ -54,10 +54,11 @@ def main(): use_fabric=not args_cli.disable_fabric, ) - # enable visualizers if requested - if args_cli.viz: - import isaaclab.sim as sim_utils - sim_utils.enable_visualizers(env_cfg) + # set visualizers based on --viz flag + if not args_cli.viz: + # Explicitly disable visualizers when --viz is not provided + env_cfg.sim.visualizer_cfgs = [] + # else: use the default visualizer_cfgs from the environment config # create environment env = gym.make(args_cli.task, cfg=env_cfg) diff --git a/scripts/environments/zero_agent.py b/scripts/environments/zero_agent.py index ca5c74d8ce7..b5e504f80eb 100644 --- a/scripts/environments/zero_agent.py +++ b/scripts/environments/zero_agent.py @@ -18,7 +18,7 @@ ) parser.add_argument("--num_envs", type=int, default=None, help="Number of environments to simulate.") parser.add_argument("--task", type=str, default=None, help="Name of the task.") -parser.add_argument("--viz", action="store_true", default=False, help="Enable visualization.") +parser.add_argument("--viz", action="store_true", default=False, help="Enable visualization for monitoring and debugging.") # append AppLauncher cli args AppLauncher.add_app_launcher_args(parser) # parse the arguments @@ -54,10 +54,11 @@ def main(): use_fabric=not args_cli.disable_fabric, ) - # enable visualizers if requested - if args_cli.viz: - import isaaclab.sim as sim_utils - sim_utils.enable_visualizers(env_cfg) + # set visualizers based on --viz flag + if not args_cli.viz: + # Explicitly disable visualizers when --viz is not provided + env_cfg.sim.visualizer_cfgs = [] + # else: use the default visualizer_cfgs from the environment config # create environment env = gym.make(args_cli.task, cfg=env_cfg) diff --git a/scripts/reinforcement_learning/rl_games/play.py b/scripts/reinforcement_learning/rl_games/play.py index f1c57f160b8..efef74ce88f 100644 --- a/scripts/reinforcement_learning/rl_games/play.py +++ b/scripts/reinforcement_learning/rl_games/play.py @@ -32,7 +32,7 @@ help="When no checkpoint provided, use the last saved model. Otherwise use the best saved model.", ) parser.add_argument("--real-time", action="store_true", default=False, help="Run in real-time, if possible.") -parser.add_argument("--viz", action="store_true", default=False, help="Enable visualization.") +parser.add_argument("--viz", action="store_true", default=False, help="Enable visualization for monitoring and debugging.") # append AppLauncher cli args AppLauncher.add_app_launcher_args(parser) # parse the arguments diff --git a/scripts/reinforcement_learning/rl_games/train.py b/scripts/reinforcement_learning/rl_games/train.py index 8376498045a..e026f5143e4 100644 --- a/scripts/reinforcement_learning/rl_games/train.py +++ b/scripts/reinforcement_learning/rl_games/train.py @@ -38,7 +38,7 @@ const=True, help="if toggled, this experiment will be tracked with Weights and Biases", ) -parser.add_argument("--viz", action="store_true", default=False, help="Enable visualization.") +parser.add_argument("--viz", action="store_true", default=False, help="Enable visualization for monitoring and debugging.") # append AppLauncher cli args AppLauncher.add_app_launcher_args(parser) # parse the arguments @@ -91,10 +91,11 @@ def main(env_cfg: ManagerBasedRLEnvCfg | DirectRLEnvCfg, agent_cfg: dict): env_cfg.scene.num_envs = args_cli.num_envs if args_cli.num_envs is not None else env_cfg.scene.num_envs env_cfg.sim.device = args_cli.device if args_cli.device is not None else env_cfg.sim.device - # enable visualizers if requested - if args_cli.viz: - import isaaclab.sim as sim_utils - sim_utils.enable_visualizers(env_cfg) + # set visualizers based on --viz flag + if not args_cli.viz: + # Explicitly disable visualizers when --viz is not provided + env_cfg.sim.visualizer_cfgs = [] + # else: use the default visualizer_cfgs from the environment config # randomly sample a seed if seed = -1 if args_cli.seed == -1: diff --git a/scripts/reinforcement_learning/rsl_rl/play.py b/scripts/reinforcement_learning/rsl_rl/play.py index 233eab273d7..0f8f67f1b1f 100644 --- a/scripts/reinforcement_learning/rsl_rl/play.py +++ b/scripts/reinforcement_learning/rsl_rl/play.py @@ -34,7 +34,7 @@ help="Use the pre-trained checkpoint from Nucleus.", ) parser.add_argument("--real-time", action="store_true", default=False, help="Run in real-time, if possible.") -parser.add_argument("--viz", action="store_true", default=False, help="Enable visualization.") +parser.add_argument("--viz", action="store_true", default=False, help="Enable visualization for monitoring and debugging.") # append RSL-RL cli arguments cli_args.add_rsl_rl_args(parser) # append AppLauncher cli args @@ -97,10 +97,17 @@ def main(env_cfg: ManagerBasedRLEnvCfg | DirectRLEnvCfg, agent_cfg: RslRlBaseRun env_cfg.seed = agent_cfg.seed env_cfg.sim.device = args_cli.device if args_cli.device is not None else env_cfg.sim.device - # enable visualizers if requested - if args_cli.viz: - import isaaclab.sim as sim_utils - sim_utils.enable_visualizers(env_cfg, train_mode=False) + # set visualizers based on --viz flag + if not args_cli.viz: + env_cfg.sim.visualizer_cfgs = [] + else: + # For play mode, ensure train_mode=False on all visualizers + if env_cfg.sim.visualizer_cfgs is not None: + if isinstance(env_cfg.sim.visualizer_cfgs, list): + for viz_cfg in env_cfg.sim.visualizer_cfgs: + viz_cfg.train_mode = False + else: + env_cfg.sim.visualizer_cfgs.train_mode = False # specify directory for logging experiments log_root_path = os.path.join("logs", "rsl_rl", agent_cfg.experiment_name) diff --git a/scripts/reinforcement_learning/rsl_rl/train.py b/scripts/reinforcement_learning/rsl_rl/train.py index 9a77fd31e80..31b94b42207 100644 --- a/scripts/reinforcement_learning/rsl_rl/train.py +++ b/scripts/reinforcement_learning/rsl_rl/train.py @@ -32,7 +32,7 @@ "--distributed", action="store_true", default=False, help="Run training with multiple GPUs or nodes." ) parser.add_argument("--export_io_descriptors", action="store_true", default=False, help="Export IO descriptors.") -parser.add_argument("--viz", action="store_true", default=False, help="Enable visualization.") +parser.add_argument("--viz", action="store_true", default=False, help="Enable visualization for monitoring and debugging") # append RSL-RL cli arguments cli_args.add_rsl_rl_args(parser) # append AppLauncher cli args @@ -120,10 +120,11 @@ def main(env_cfg: ManagerBasedRLEnvCfg | DirectRLEnvCfg, agent_cfg: RslRlBaseRun env_cfg.seed = agent_cfg.seed env_cfg.sim.device = args_cli.device if args_cli.device is not None else env_cfg.sim.device - # enable visualizers if requested - if args_cli.viz: - import isaaclab.sim as sim_utils - sim_utils.enable_visualizers(env_cfg) + # set visualizers based on --viz flag + if not args_cli.viz: + # Explicitly disable visualizers when --viz is not provided + env_cfg.sim.visualizer_cfgs = [] + # else: use the default visualizer_cfgs from the environment config # multi-gpu training configuration if args_cli.distributed: diff --git a/scripts/reinforcement_learning/sb3/play.py b/scripts/reinforcement_learning/sb3/play.py index ec9ba0714cb..af3b0ae6ce0 100644 --- a/scripts/reinforcement_learning/sb3/play.py +++ b/scripts/reinforcement_learning/sb3/play.py @@ -39,7 +39,7 @@ default=False, help="Use a slower SB3 wrapper but keep all the extra training info.", ) -parser.add_argument("--viz", action="store_true", default=False, help="Enable visualization.") +parser.add_argument("--viz", action="store_true", default=False, help="Enable visualization for monitoring and debugging.") # append AppLauncher cli args AppLauncher.add_app_launcher_args(parser) # parse the arguments diff --git a/scripts/reinforcement_learning/sb3/train.py b/scripts/reinforcement_learning/sb3/train.py index d96b1a5af6e..073e316b15c 100644 --- a/scripts/reinforcement_learning/sb3/train.py +++ b/scripts/reinforcement_learning/sb3/train.py @@ -32,7 +32,7 @@ default=False, help="Use a slower SB3 wrapper but keep all the extra training info.", ) -parser.add_argument("--viz", action="store_true", default=False, help="Enable visualization.") +parser.add_argument("--viz", action="store_true", default=False, help="Enable visualization for monitoring and debugging.") # append AppLauncher cli args AppLauncher.add_app_launcher_args(parser) # parse the arguments @@ -114,10 +114,11 @@ def main(env_cfg: ManagerBasedRLEnvCfg | DirectRLEnvCfg, agent_cfg: dict): env_cfg.seed = agent_cfg["seed"] env_cfg.sim.device = args_cli.device if args_cli.device is not None else env_cfg.sim.device - # enable visualizers if requested - if args_cli.viz: - import isaaclab.sim as sim_utils - sim_utils.enable_visualizers(env_cfg) + # set visualizers based on --viz flag + if not args_cli.viz: + # Explicitly disable visualizers when --viz is not provided + env_cfg.sim.visualizer_cfgs = [] + # else: use the default visualizer_cfgs from the environment config # directory for logging into run_info = datetime.now().strftime("%Y-%m-%d_%H-%M-%S") diff --git a/scripts/reinforcement_learning/skrl/play.py b/scripts/reinforcement_learning/skrl/play.py index d6103b2cc53..6a380a4665c 100644 --- a/scripts/reinforcement_learning/skrl/play.py +++ b/scripts/reinforcement_learning/skrl/play.py @@ -46,7 +46,7 @@ help="The RL algorithm used for training the skrl agent.", ) parser.add_argument("--real-time", action="store_true", default=False, help="Run in real-time, if possible.") -parser.add_argument("--viz", action="store_true", default=False, help="Enable visualization.") +parser.add_argument("--viz", action="store_true", default=False, help="Enable visualization for monitoring and debugging.") # append AppLauncher cli args AppLauncher.add_app_launcher_args(parser) diff --git a/scripts/reinforcement_learning/skrl/train.py b/scripts/reinforcement_learning/skrl/train.py index e8474545a24..bac4b0fe64b 100644 --- a/scripts/reinforcement_learning/skrl/train.py +++ b/scripts/reinforcement_learning/skrl/train.py @@ -44,7 +44,7 @@ choices=["AMP", "PPO", "IPPO", "MAPPO"], help="The RL algorithm used for training the skrl agent.", ) -parser.add_argument("--viz", action="store_true", default=False, help="Enable visualization.") +parser.add_argument("--viz", action="store_true", default=False, help="Enable visualization for monitoring and debugging.") # append AppLauncher cli args AppLauncher.add_app_launcher_args(parser) @@ -114,10 +114,11 @@ def main(env_cfg: ManagerBasedRLEnvCfg | DirectRLEnvCfg, agent_cfg: dict): env_cfg.scene.num_envs = args_cli.num_envs if args_cli.num_envs is not None else env_cfg.scene.num_envs env_cfg.sim.device = args_cli.device if args_cli.device is not None else env_cfg.sim.device - # enable visualizers if requested - if args_cli.viz: - import isaaclab.sim as sim_utils - sim_utils.enable_visualizers(env_cfg) + # set visualizers based on --viz flag + if not args_cli.viz: + # Explicitly disable visualizers when --viz is not provided + env_cfg.sim.visualizer_cfgs = [] + # else: use the default visualizer_cfgs from the environment config # multi-gpu training config if args_cli.distributed: diff --git a/scripts/sim2sim_transfer/rsl_rl_transfer.py b/scripts/sim2sim_transfer/rsl_rl_transfer.py index 168abb8356b..2ce2d4cf42e 100644 --- a/scripts/sim2sim_transfer/rsl_rl_transfer.py +++ b/scripts/sim2sim_transfer/rsl_rl_transfer.py @@ -29,7 +29,7 @@ help="Use the pre-trained checkpoint from Nucleus.", ) parser.add_argument("--real-time", action="store_true", default=False, help="Run in real-time, if possible.") -parser.add_argument("--viz", action="store_true", default=False, help="Enable visualization.") +parser.add_argument("--viz", action="store_true", default=False, help="Enable visualization for monitoring and debugging.") # Joint ordering arguments parser.add_argument( "--policy_transfer_file", @@ -149,10 +149,11 @@ def main(): use_fabric=not args_cli.disable_fabric, ) - # enable visualizers if requested - if args_cli.viz: - import isaaclab.sim as sim_utils - sim_utils.enable_visualizers(env_cfg) + # set visualizers based on --viz flag + if not args_cli.viz: + # Explicitly disable visualizers when --viz is not provided + env_cfg.sim.visualizer_cfgs = [] + # else: use the default visualizer_cfgs from the environment config agent_cfg: RslRlOnPolicyRunnerCfg = cli_args.parse_rsl_rl_cfg(task_name, args_cli) # specify directory for logging experiments diff --git a/source/isaaclab/isaaclab/sim/simulation_cfg.py b/source/isaaclab/isaaclab/sim/simulation_cfg.py index c9dc1c89f9b..5cab905e249 100644 --- a/source/isaaclab/isaaclab/sim/simulation_cfg.py +++ b/source/isaaclab/isaaclab/sim/simulation_cfg.py @@ -197,9 +197,8 @@ class SimulationCfg: render_cfg: RenderCfg = RenderCfg() """Render settings. Default is RenderCfg().""" - # visualizer_cfgs: list[VisualizerCfg] | VisualizerCfg | None = None - visualizer_cfgs: list[VisualizerCfg] | VisualizerCfg | None = OVVisualizerCfg(env_ids_to_viz=[0]) - """Visualizer settings. Default is None (no visualization). + visualizer_cfgs: list[VisualizerCfg] | VisualizerCfg | None = NewtonVisualizerCfg() + """Visualizer settings. Default is NewtonVisualizerCfg(). This field supports multiple visualizer backends for debug visualization and monitoring during simulation. It accepts: @@ -208,28 +207,32 @@ class SimulationCfg: - None or empty list: No visualizers will be created Supported visualizer backends: - - NewtonVisualizerCfg: Lightweight OpenGL-based visualizer + - NewtonVisualizerCfg: Lightweight OpenGL-based visualizer (default) - OVVisualizerCfg: Omniverse-based high-fidelity visualizer - RerunVisualizerCfg: Web-based Rerun visualizer Examples: - # No visualizers (default) + # Disable all visualizers + cfg.sim.visualizer_cfgs = [] + + # Use default visualizer (NewtonVisualizerCfg) cfg = SimulationCfg() - # Single visualizer - from isaaclab.sim.visualizers import NewtonVisualizerCfg - cfg = SimulationCfg(visualizer_cfgs=NewtonVisualizerCfg()) + # Single custom visualizer + from isaaclab.sim.visualizers import OVVisualizerCfg + cfg = SimulationCfg(visualizer_cfgs=OVVisualizerCfg()) - # Multiple visualizers + # Multiple visualizers with custom configuration from isaaclab.sim.visualizers import NewtonVisualizerCfg, RerunVisualizerCfg cfg = SimulationCfg(visualizer_cfgs=[ - NewtonVisualizerCfg(), - RerunVisualizerCfg() + NewtonVisualizerCfg(env_ids_to_viz=[0], camera_position=(10.0, 0.0, 3.0)), + RerunVisualizerCfg(server_address="127.0.0.1:9876") ]) Note: Visualizers are separate from rendering backends (for cameras/sensors). They are intended for debug visualization and monitoring only. + Visualizers are automatically initialized in SimulationContext during reset(). """ create_stage_in_memory: bool = False diff --git a/source/isaaclab/isaaclab/sim/visualizers/__init__.py b/source/isaaclab/isaaclab/sim/visualizers/__init__.py index 1abc058258c..3a2dd027d56 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/__init__.py +++ b/source/isaaclab/isaaclab/sim/visualizers/__init__.py @@ -12,7 +12,7 @@ Supported visualizers: - Newton OpenGL Visualizer: Lightweight OpenGL-based visualizer - Omniverse Visualizer: High-fidelity Omniverse-based visualizer using Isaac Sim viewport -- Rerun Visualizer: Web-based visualizer using the rerun library (coming soon) +- Rerun Visualizer: Web-based Rerun visualizer with recording and timeline scrubbing Visualizer Registry ------------------- @@ -34,10 +34,6 @@ from .ov_visualizer_cfg import OVVisualizerCfg from .rerun_visualizer_cfg import RerunVisualizerCfg -# NOTE: Visualizer implementations are NOT imported here to avoid loading -# dependencies for unused visualizers (REQ-10: clean dependency handling). -# They are lazy-loaded via the registry when actually needed. - if TYPE_CHECKING: from typing import Type from .newton_visualizer import NewtonVisualizer @@ -56,16 +52,12 @@ "get_visualizer_class", ] -# Note: Visualizer implementation classes (NewtonVisualizer, OVVisualizer, RerunVisualizer) -# are not exported to avoid eager loading. Access them via get_visualizer_class() or -# VisualizerCfg.create_visualizer() instead. - - +# Register only selected visualizers to reduce unnecessary imports def get_visualizer_class(name: str) -> Type[Visualizer] | None: """Get a visualizer class by name (lazy-loaded). Visualizer classes are imported only when requested to avoid loading - unnecessary dependencies (REQ-10: clean dependency handling). + unnecessary dependencies. Args: name: Visualizer type name (e.g., 'newton', 'rerun', 'omniverse', 'ov'). diff --git a/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py b/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py index 30d41f96cd7..bdeca85642d 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py +++ b/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py @@ -25,13 +25,14 @@ class NewtonViewerGL(ViewerGL): - Rendering pause: Stops rendering updates, continues physics (SPACE key) """ - def __init__(self, *args, train_mode: bool = True, metadata: dict | None = None, **kwargs): + def __init__(self, *args, train_mode: bool = True, metadata: dict | None = None, update_frequency: int = 1, **kwargs): super().__init__(*args, **kwargs) self._paused_training = False self._paused_rendering = False self._is_train_mode = train_mode self._metadata = metadata or {} self._fallback_draw_controls = False + self._update_frequency = update_frequency try: self.register_ui_callback(self._render_training_controls, position="side") @@ -67,6 +68,21 @@ def _render_training_controls(self, imgui): self._paused_rendering = not self._paused_rendering self._paused = self._paused_rendering + # Visualizer update frequency control + imgui.text("Visualizer Update Frequency") + current_frequency = self._update_frequency + changed, new_frequency = imgui.slider_int( + "##VisualizerUpdateFreq", current_frequency, 1, 20, f"Every {current_frequency} frames" + ) + if changed: + self._update_frequency = new_frequency + + if imgui.is_item_hovered(): + imgui.set_tooltip( + "Controls visualizer update frequency\nlower values -> more responsive visualizer but slower" + " training\nhigher values -> less responsive visualizer but faster training" + ) + def on_key_press(self, symbol, modifiers): if self.ui.is_capturing(): return @@ -234,6 +250,7 @@ def __init__(self, cfg: NewtonVisualizerCfg): self._step_counter = 0 self._model = None self._state = None + self._update_frequency = cfg.update_frequency def initialize(self, scene_data: dict[str, Any] | None = None) -> None: """Initialize visualizer with scene data.""" @@ -265,6 +282,7 @@ def initialize(self, scene_data: dict[str, Any] | None = None) -> None: height=self.cfg.window_height, train_mode=self.cfg.train_mode, metadata=metadata, + update_frequency=self.cfg.update_frequency, ) # Set the model @@ -308,9 +326,15 @@ def step(self, dt: float, state: Any | None = None) -> None: return self._sim_time += dt + self._step_counter += 1 if state is not None: self._state = state + # Only update visualizer at the specified frequency + update_frequency = self._viewer._update_frequency if self._viewer else self._update_frequency + if self._step_counter % update_frequency != 0: + return + try: if not self._viewer.is_paused(): self._viewer.begin_frame(self._sim_time) diff --git a/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer_cfg.py b/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer_cfg.py index f604e3c7ea8..c8f64220dda 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer_cfg.py +++ b/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer_cfg.py @@ -73,4 +73,7 @@ class NewtonVisualizerCfg(VisualizerCfg): light_color: tuple[float, float, float] = (1.0, 1.0, 1.0) """Light color RGB [0,1].""" + update_frequency: int = 1 + """Visualizer update frequency (updates every N frames). Lower = more responsive but slower training.""" + diff --git a/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer.py b/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer.py index 6071b1445f5..b96616cf85b 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer.py +++ b/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer.py @@ -479,6 +479,8 @@ def _setup_env_filtering(self, num_envs: int) -> None: Args: num_envs: Total number of environments. """ + # TODO, still testing, also very hackey + import warp as wp # Create world offsets array From 6f4ff19c13ebdd7d05beb5171369703ce80a43eb Mon Sep 17 00:00:00 2001 From: mtrepte Date: Wed, 19 Nov 2025 11:53:05 -0800 Subject: [PATCH 15/24] clean --- .../isaaclab/sim/simulation_context.py | 18 +++----- .../sim/visualizers/newton_visualizer.py | 31 +++++++------ .../isaaclab/sim/visualizers/ov_visualizer.py | 22 +++++++++- .../sim/visualizers/rerun_visualizer.py | 44 +++++++++---------- 4 files changed, 63 insertions(+), 52 deletions(-) diff --git a/source/isaaclab/isaaclab/sim/simulation_context.py b/source/isaaclab/isaaclab/sim/simulation_context.py index 45b470e7efe..3c2eaaaf80a 100644 --- a/source/isaaclab/isaaclab/sim/simulation_context.py +++ b/source/isaaclab/isaaclab/sim/simulation_context.py @@ -564,17 +564,10 @@ def initialize_visualizers(self) -> None: try: visualizer = viz_cfg.create_visualizer() - # Prepare scene data from Newton physics backend + # Pass minimal generic scene data - visualizers fetch backend-specific data themselves scene_data = { - "model": NewtonManager._model, - "state": NewtonManager._state_0, + "simulation_context": self, "usd_stage": self.stage, - "metadata": { - "physics_backend": "newton", - "num_envs": NewtonManager._num_envs if NewtonManager._num_envs is not None else 0, - "gravity_vector": NewtonManager._gravity_vector, - "clone_physics_only": NewtonManager._clone_physics_only, - } } # Initialize visualizer with scene data @@ -617,14 +610,15 @@ def step_visualizers(self, dt: float) -> None: # Handle training pause - block until resumed while visualizer.is_training_paused() and visualizer.is_running(): - visualizer.step(0.0, state=NewtonManager._state_0) + # Visualizers fetch backend-specific state themselves + visualizer.step(0.0, state=None) # Skip rendering if visualizer has rendering paused if visualizer.is_rendering_paused(): continue - # Normal step: pass updated Newton state - visualizer.step(dt, state=NewtonManager._state_0) + # Normal step: visualizers fetch backend-specific state themselves + visualizer.step(dt, state=None) except Exception as e: omni.log.error(f"Error stepping visualizer '{type(visualizer).__name__}': {e}") diff --git a/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py b/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py index bdeca85642d..6be9f996f71 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py +++ b/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py @@ -257,24 +257,25 @@ def initialize(self, scene_data: dict[str, Any] | None = None) -> None: if self._is_initialized: return - metadata = {} - if scene_data is not None: - self._model = scene_data.get("model") - self._state = scene_data.get("state") - metadata = scene_data.get("metadata", {}) + # Fetch Newton-specific data from NewtonManager + from isaaclab.sim._impl.newton_manager import NewtonManager - physics_backend = metadata.get("physics_backend", "unknown") - if physics_backend != "newton" and physics_backend != "unknown": - raise RuntimeError( - f"Newton visualizer requires Newton physics backend, got '{physics_backend}'. " - f"Use OVVisualizer for other backends." - ) + self._model = NewtonManager._model + self._state = NewtonManager._state_0 if self._model is None: raise RuntimeError( - "Newton visualizer requires Newton Model in scene_data['model']. " + "Newton visualizer requires Newton Model. " "Ensure Newton physics is initialized first." ) + + # Build metadata from NewtonManager + metadata = { + "physics_backend": "newton", + "num_envs": NewtonManager._num_envs if NewtonManager._num_envs is not None else 0, + "gravity_vector": NewtonManager._gravity_vector, + "clone_physics_only": NewtonManager._clone_physics_only, + } # Create the viewer with train_mode and metadata self._viewer = NewtonViewerGL( @@ -327,8 +328,10 @@ def step(self, dt: float, state: Any | None = None) -> None: self._sim_time += dt self._step_counter += 1 - if state is not None: - self._state = state + + # Fetch updated state from NewtonManager + from isaaclab.sim._impl.newton_manager import NewtonManager + self._state = NewtonManager._state_0 # Only update visualizer at the specified frequency update_frequency = self._viewer._update_frequency if self._viewer else self._update_frequency diff --git a/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer.py b/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer.py index a7f4a69c72f..e7f18fa2866 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer.py +++ b/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer.py @@ -39,15 +39,33 @@ def initialize(self, scene_data: dict[str, Any] | None = None) -> None: omni.log.warn("[OVVisualizer] Already initialized.") return - metadata = {} usd_stage = None + simulation_context = None if scene_data is not None: usd_stage = scene_data.get("usd_stage") - metadata = scene_data.get("metadata", {}) + simulation_context = scene_data.get("simulation_context") if usd_stage is None: raise RuntimeError("OV visualizer requires a USD stage.") + # Build metadata from simulation context if available + metadata = {} + if simulation_context is not None: + # Try to get num_envs from the simulation context's scene if available + num_envs = 0 + if hasattr(simulation_context, 'scene') and simulation_context.scene is not None: + if hasattr(simulation_context.scene, 'num_envs'): + num_envs = simulation_context.scene.num_envs + + # Detect physics backend (could be extended to check actual backend type) + physics_backend = "newton" # Default for now, could be made more sophisticated + + metadata = { + "num_envs": num_envs, + "physics_backend": physics_backend, + "env_prim_pattern": "/World/envs/env_{}", # Standard pattern + } + self._ensure_simulation_app() self._setup_viewport(usd_stage, metadata) diff --git a/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer.py b/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer.py index b96616cf85b..b29d31ce2a0 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer.py +++ b/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer.py @@ -273,37 +273,33 @@ def initialize(self, scene_data: dict[str, Any] | None = None) -> None: omni.log.warn("[RerunVisualizer] Already initialized. Skipping re-initialization.") return - # Extract scene data - metadata = {} - if scene_data is not None: - self._model = scene_data.get("model") - self._state = scene_data.get("state") - metadata = scene_data.get("metadata", {}) - - # Validate physics backend - physics_backend = metadata.get("physics_backend", "unknown") - if physics_backend != "newton" and physics_backend != "unknown": - raise RuntimeError( - f"Rerun visualizer currently requires Newton physics backend, " - f"but '{physics_backend}' is running. " - f"Please use a compatible visualizer for {physics_backend} physics " - f"(e.g., OVVisualizer).\n\n" - f"Future versions will support multiple physics backends." - ) + # Fetch Newton-specific data from NewtonManager + from isaaclab.sim._impl.newton_manager import NewtonManager + + self._model = NewtonManager._model + self._state = NewtonManager._state_0 # Validate required Newton data if self._model is None: raise RuntimeError( - "Rerun visualizer requires a Newton Model in scene_data['model']. " + "Rerun visualizer requires a Newton Model. " "Make sure Newton physics is initialized before creating the visualizer." ) if self._state is None: omni.log.warn( - "[RerunVisualizer] No Newton State provided in scene_data['state']. " + "[RerunVisualizer] No Newton State available. " "Visualization may not work correctly." ) + # Build metadata from NewtonManager + metadata = { + "physics_backend": "newton", + "num_envs": NewtonManager._num_envs if NewtonManager._num_envs is not None else 0, + "gravity_vector": NewtonManager._gravity_vector, + "clone_physics_only": NewtonManager._clone_physics_only, + } + # Create Newton ViewerRerun wrapper try: if self.cfg.record_to_rrd: @@ -348,7 +344,7 @@ def step(self, dt: float, state: Any | None = None) -> None: """Update visualizer each step. This method: - 1. Updates state (if provided) + 1. Fetches updated state from NewtonManager 2. Logs current state to Rerun (transforms, meshes) 3. Actively logs markers (if enabled) 4. Actively logs plot data (if enabled) @@ -360,15 +356,15 @@ def step(self, dt: float, state: Any | None = None) -> None: Args: dt: Time step in seconds. - state: Updated physics state (e.g., newton.State). + state: Unused (deprecated parameter, kept for API compatibility). """ if not self._is_initialized or self._viewer is None: omni.log.warn("[RerunVisualizer] Not initialized. Call initialize() first.") return - # Update state if provided - if state is not None: - self._state = state + # Fetch updated state from NewtonManager + from isaaclab.sim._impl.newton_manager import NewtonManager + self._state = NewtonManager._state_0 # Update internal time self._sim_time += dt From 3d154aadb6b2bbd82d70e9a841bfcf32b171eadb Mon Sep 17 00:00:00 2001 From: mtrepte Date: Wed, 19 Nov 2025 13:58:21 -0800 Subject: [PATCH 16/24] add OV ui auto enabling to live plots --- .../isaaclab/envs/ui/base_env_window.py | 34 +++++++++++++++++++ .../sim/visualizers/newton_visualizer.py | 13 +++++-- .../sim/visualizers/newton_visualizer_cfg.py | 8 ++--- .../isaaclab/sim/visualizers/ov_visualizer.py | 9 +++-- .../sim/visualizers/rerun_visualizer.py | 19 +++++++---- .../sim/visualizers/visualizer_cfg.py | 10 +++++- .../ui/widgets/manager_live_visualizer.py | 4 ++- 7 files changed, 79 insertions(+), 18 deletions(-) diff --git a/source/isaaclab/isaaclab/envs/ui/base_env_window.py b/source/isaaclab/isaaclab/envs/ui/base_env_window.py index 6d10ab42c26..1e7aa24a7cc 100644 --- a/source/isaaclab/isaaclab/envs/ui/base_env_window.py +++ b/source/isaaclab/isaaclab/envs/ui/base_env_window.py @@ -66,6 +66,9 @@ def __init__(self, env: ManagerBasedEnv, window_name: str = "IsaacLab"): # Listeners for environment selection changes self._ui_listeners: list[ManagerLiveVisualizer] = [] + # Check if any visualizer has live plots enabled + self._enable_live_plots = self._check_live_plots_enabled() + print("Creating window for environment.") # create window for UI self.ui_window = omni.ui.Window( @@ -102,6 +105,29 @@ def __del__(self): self.ui_window.destroy() self.ui_window = None + """ + Helper methods. + """ + + def _check_live_plots_enabled(self) -> bool: + """Check if any visualizer has live plots enabled. + + Returns: + True if any visualizer supports and has live plots enabled, False otherwise. + """ + # Check if simulation has visualizers + if not hasattr(self.env.sim, '_visualizers'): + return False + + # Check each visualizer + for visualizer in self.env.sim._visualizers: + # Check if visualizer supports live plots and has it enabled + if hasattr(visualizer, 'cfg') and hasattr(visualizer.cfg, 'enable_live_plots'): + if visualizer.supports_live_plots() and visualizer.cfg.enable_live_plots: + return True + + return False + """ Build sub-sections of the UI. """ @@ -421,6 +447,11 @@ def _create_debug_vis_ui_element(self, name: str, elem: object): is_checked = (hasattr(elem.cfg, "debug_vis") and elem.cfg.debug_vis) or ( hasattr(elem, "debug_vis") and elem.debug_vis ) + + # Auto-enable live plots for ManagerLiveVisualizer if visualizer has enable_live_plots=True + if isinstance(elem, ManagerLiveVisualizer) and self._enable_live_plots: + is_checked = True + self.ui_window_elements[f"{name}_cb"] = SimpleCheckBox( model=omni.ui.SimpleBoolModel(), enabled=elem.has_debug_vis_implementation, @@ -434,6 +465,9 @@ def _create_debug_vis_ui_element(self, name: str, elem: object): self.ui_window_elements[f"{name}_panel"] = omni.ui.Frame(width=omni.ui.Fraction(1)) if not elem.set_vis_frame(self.ui_window_elements[f"{name}_panel"]): print(f"Frame failed to set for ManagerLiveVisualizer: {name}") + + # Pass the enable_live_plots flag to the visualizer + elem._auto_expand_frames = self._enable_live_plots # Add listener for environment selection changes if isinstance(elem, ManagerLiveVisualizer): diff --git a/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py b/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py index 6be9f996f71..0c3ddf83b29 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py +++ b/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py @@ -386,8 +386,15 @@ def is_rendering_paused(self) -> bool: def _setup_env_filtering(self, num_envs: int) -> None: """Setup environment filtering using world offsets. - WIP: Moves non-visualized environments far away (10000 units) to hide them. - Future: Could use more sophisticated filtering or culling. + NOTE: This uses visualization-only offsets that do NOT affect physics simulation. + Newton's world_offsets only shift the rendered position of environments, not their + physical positions. This is confirmed by Newton's test_visual_separation test. + + Current approach: Moves non-visualized environments far away (10000 units) to hide them. + This works but is not ideal. Future improvements could include: + - Proper culling at the viewer level + - Selective state logging (only log visualized envs) + - Custom rendering callbacks Args: num_envs: Total number of environments. @@ -398,7 +405,7 @@ def _setup_env_filtering(self, num_envs: int) -> None: offsets = wp.zeros(num_envs, dtype=wp.vec3, device=self._viewer.device) offsets_np = offsets.numpy() - # Move non-visualized environments far away + # Move non-visualized environments far away (visualization-only, doesn't affect physics) visualized_set = set(self.cfg.env_ids_to_viz) for world_idx in range(num_envs): if world_idx not in visualized_set: diff --git a/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer_cfg.py b/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer_cfg.py index c8f64220dda..bd571741cf2 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer_cfg.py +++ b/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer_cfg.py @@ -40,6 +40,9 @@ class NewtonVisualizerCfg(VisualizerCfg): train_mode: bool = True """Training mode (True) shows rendering pause controls, play mode (False) hides them.""" + update_frequency: int = 1 + """Visualizer update frequency (updates every N frames). Lower = more responsive but slower training.""" + up_axis: Literal["X", "Y", "Z"] = "Z" """World up axis.""" @@ -72,8 +75,3 @@ class NewtonVisualizerCfg(VisualizerCfg): light_color: tuple[float, float, float] = (1.0, 1.0, 1.0) """Light color RGB [0,1].""" - - update_frequency: int = 1 - """Visualizer update frequency (updates every N frames). Lower = more responsive but slower training.""" - - diff --git a/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer.py b/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer.py index e7f18fa2866..9247f5a6758 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer.py +++ b/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer.py @@ -114,8 +114,13 @@ def supports_markers(self) -> bool: return True def supports_live_plots(self) -> bool: - # Should we automatically focus the live plots window? - """Supports live plots via Isaac Lab UI.""" + """Supports live plots via Isaac Lab UI. + + When enable_live_plots=True in OVVisualizerCfg: + - Automatically enables all manager visualizers (checkboxes checked) + - Keeps plot frames expanded by default + - Plots appear in the IsaacLab window docked to the right of the viewport + """ return True # ------------------------------------------------------------------ diff --git a/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer.py b/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer.py index b29d31ce2a0..829b1127709 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer.py +++ b/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer.py @@ -329,6 +329,7 @@ def initialize(self, scene_data: dict[str, Any] | None = None) -> None: # Log initialization viz_envs = len(self.cfg.env_ids_to_viz) if self.cfg.env_ids_to_viz else num_envs + physics_backend = metadata.get("physics_backend", "newton") omni.log.info( f"[RerunVisualizer] Initialized with {viz_envs}/{num_envs} environments " f"(physics: {physics_backend})" @@ -357,7 +358,8 @@ def step(self, dt: float, state: Any | None = None) -> None: Args: dt: Time step in seconds. state: Unused (deprecated parameter, kept for API compatibility). - """ + """e + if not self._is_initialized or self._viewer is None: omni.log.warn("[RerunVisualizer] Not initialized. Call initialize() first.") return @@ -469,21 +471,26 @@ def register_plots(self, plots: dict[str, Any]) -> None: def _setup_env_filtering(self, num_envs: int) -> None: """Setup environment filtering using world offsets. - WIP: Moves non-visualized environments far away (10000 units) to hide them. - Future: Could implement proper state filtering before logging. + NOTE: This uses visualization-only offsets that do NOT affect physics simulation. + Newton's world_offsets only shift the rendered/logged position of environments, not their + physical positions. This is confirmed by Newton's test_visual_separation test. + + Current approach: Moves non-visualized environments far away (10000 units) to hide them. + This works but is not ideal. Future improvements could include: + - Proper filtering at the logging level (only log selected env transforms) + - Custom logging callbacks for partial visualization + - State slicing before logging Args: num_envs: Total number of environments. """ - # TODO, still testing, also very hackey - import warp as wp # Create world offsets array offsets = wp.zeros(num_envs, dtype=wp.vec3, device=self._viewer.device) offsets_np = offsets.numpy() - # Move non-visualized environments far away + # Move non-visualized environments far away (visualization-only, doesn't affect physics) visualized_set = set(self.cfg.env_ids_to_viz) for world_idx in range(num_envs): if world_idx not in visualized_set: diff --git a/source/isaaclab/isaaclab/sim/visualizers/visualizer_cfg.py b/source/isaaclab/isaaclab/sim/visualizers/visualizer_cfg.py index abdc7ecc5e6..df511499804 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/visualizer_cfg.py +++ b/source/isaaclab/isaaclab/sim/visualizers/visualizer_cfg.py @@ -29,7 +29,15 @@ class VisualizerCfg: """Enable visualization markers (debug drawing).""" enable_live_plots: bool = True - """Enable live plotting of data.""" + """Enable live plotting of data. + + When set to True for OVVisualizer: + - Automatically checks the checkboxes for all manager visualizers (Actions, Observations, Rewards, etc.) + - Keeps the plot frames expanded by default (not collapsed) + - Makes the live plots visible immediately in the IsaacLab window (docked to the right of the viewport) + + This provides a better out-of-the-box experience when you want to monitor training metrics. + """ def get_visualizer_type(self) -> str: """Get the visualizer type identifier.""" diff --git a/source/isaaclab/isaaclab/ui/widgets/manager_live_visualizer.py b/source/isaaclab/isaaclab/ui/widgets/manager_live_visualizer.py index a7cc31c070b..9070e9a4990 100644 --- a/source/isaaclab/isaaclab/ui/widgets/manager_live_visualizer.py +++ b/source/isaaclab/isaaclab/ui/widgets/manager_live_visualizer.py @@ -68,6 +68,7 @@ def __init__(self, manager: ManagerBase, cfg: ManagerLiveVisualizerCfg = Manager self._viewer_env_idx = 0 self._vis_frame: omni.ui.Frame self._vis_window: omni.ui.Window + self._auto_expand_frames: bool = False # Set by BaseEnvWindow if visualizer has enable_live_plots=True # evaluate chosen terms if no terms provided use all available. self.term_names = [] @@ -231,7 +232,8 @@ def _set_debug_vis_impl(self, debug_vis: bool): f"ManagerLiveVisualizer: Term ({name}) is not a supported data type for" " visualization." ) - frame.collapsed = True + # Keep frames expanded if auto-expand is enabled (when visualizer has enable_live_plots=True) + frame.collapsed = not self._auto_expand_frames self._debug_vis = debug_vis From 0f8dda39633c941efbd0b2740a3796b62d6244b8 Mon Sep 17 00:00:00 2001 From: mtrepte Date: Fri, 21 Nov 2025 00:51:33 -0800 Subject: [PATCH 17/24] fb draft --- scripts/environments/random_agent.py | 6 - scripts/environments/zero_agent.py | 6 - .../reinforcement_learning/rl_games/play.py | 4 +- .../reinforcement_learning/rl_games/train.py | 7 - scripts/reinforcement_learning/rsl_rl/play.py | 13 -- .../reinforcement_learning/rsl_rl/train.py | 7 - scripts/reinforcement_learning/sb3/play.py | 3 +- scripts/reinforcement_learning/sb3/train.py | 7 - scripts/reinforcement_learning/skrl/play.py | 3 +- scripts/reinforcement_learning/skrl/train.py | 7 - scripts/sim2sim_transfer/rsl_rl_transfer.py | 6 - .../isaaclab/sim/scene_data_provider.py | 123 ++++++++++++++++++ .../isaaclab/isaaclab/sim/simulation_cfg.py | 8 +- .../isaaclab/sim/simulation_context.py | 29 ++++- .../{sim => }/visualizers/__init__.py | 0 .../visualizers/newton_visualizer.py | 91 +++++-------- .../visualizers/newton_visualizer_cfg.py | 3 - .../{sim => }/visualizers/ov_visualizer.py | 52 +------- .../visualizers/ov_visualizer_cfg.py | 0 .../{sim => }/visualizers/rerun_visualizer.py | 90 ++++--------- .../visualizers/rerun_visualizer_cfg.py | 0 .../{sim => }/visualizers/visualizer.py | 0 .../{sim => }/visualizers/visualizer_cfg.py | 5 +- source/isaaclab/setup.py | 2 + .../isaaclab_tasks/utils/parse_cfg.py | 14 +- 25 files changed, 223 insertions(+), 263 deletions(-) create mode 100644 source/isaaclab/isaaclab/sim/scene_data_provider.py rename source/isaaclab/isaaclab/{sim => }/visualizers/__init__.py (100%) rename source/isaaclab/isaaclab/{sim => }/visualizers/newton_visualizer.py (81%) rename source/isaaclab/isaaclab/{sim => }/visualizers/newton_visualizer_cfg.py (94%) rename source/isaaclab/isaaclab/{sim => }/visualizers/ov_visualizer.py (87%) rename source/isaaclab/isaaclab/{sim => }/visualizers/ov_visualizer_cfg.py (100%) rename source/isaaclab/isaaclab/{sim => }/visualizers/rerun_visualizer.py (85%) rename source/isaaclab/isaaclab/{sim => }/visualizers/rerun_visualizer_cfg.py (100%) rename source/isaaclab/isaaclab/{sim => }/visualizers/visualizer.py (100%) rename source/isaaclab/isaaclab/{sim => }/visualizers/visualizer_cfg.py (87%) diff --git a/scripts/environments/random_agent.py b/scripts/environments/random_agent.py index 2676710c2bb..c7d584ef924 100644 --- a/scripts/environments/random_agent.py +++ b/scripts/environments/random_agent.py @@ -18,7 +18,6 @@ ) parser.add_argument("--num_envs", type=int, default=None, help="Number of environments to simulate.") parser.add_argument("--task", type=str, default=None, help="Name of the task.") -parser.add_argument("--viz", action="store_true", default=False, help="Enable visualization for monitoring and debugging.") # append AppLauncher cli args AppLauncher.add_app_launcher_args(parser) # parse the arguments @@ -54,11 +53,6 @@ def main(): use_fabric=not args_cli.disable_fabric, ) - # set visualizers based on --viz flag - if not args_cli.viz: - # Explicitly disable visualizers when --viz is not provided - env_cfg.sim.visualizer_cfgs = [] - # else: use the default visualizer_cfgs from the environment config # create environment env = gym.make(args_cli.task, cfg=env_cfg) diff --git a/scripts/environments/zero_agent.py b/scripts/environments/zero_agent.py index b5e504f80eb..50017af4ba9 100644 --- a/scripts/environments/zero_agent.py +++ b/scripts/environments/zero_agent.py @@ -18,7 +18,6 @@ ) parser.add_argument("--num_envs", type=int, default=None, help="Number of environments to simulate.") parser.add_argument("--task", type=str, default=None, help="Name of the task.") -parser.add_argument("--viz", action="store_true", default=False, help="Enable visualization for monitoring and debugging.") # append AppLauncher cli args AppLauncher.add_app_launcher_args(parser) # parse the arguments @@ -54,11 +53,6 @@ def main(): use_fabric=not args_cli.disable_fabric, ) - # set visualizers based on --viz flag - if not args_cli.viz: - # Explicitly disable visualizers when --viz is not provided - env_cfg.sim.visualizer_cfgs = [] - # else: use the default visualizer_cfgs from the environment config # create environment env = gym.make(args_cli.task, cfg=env_cfg) diff --git a/scripts/reinforcement_learning/rl_games/play.py b/scripts/reinforcement_learning/rl_games/play.py index efef74ce88f..6ce539a55c0 100644 --- a/scripts/reinforcement_learning/rl_games/play.py +++ b/scripts/reinforcement_learning/rl_games/play.py @@ -32,7 +32,6 @@ help="When no checkpoint provided, use the last saved model. Otherwise use the best saved model.", ) parser.add_argument("--real-time", action="store_true", default=False, help="Run in real-time, if possible.") -parser.add_argument("--viz", action="store_true", default=False, help="Enable visualization for monitoring and debugging.") # append AppLauncher cli args AppLauncher.add_app_launcher_args(parser) # parse the arguments @@ -79,7 +78,8 @@ def main(): """Play with RL-Games agent.""" task_name = args_cli.task.split(":")[-1] # parse env configuration - env_cfg = parse_env_cfg(args_cli.task, device=args_cli.device, num_envs=args_cli.num_envs, use_fabric=not args_cli.disable_fabric, visualize=args_cli.viz, train_mode=False) + env_cfg = parse_env_cfg(args_cli.task, device=args_cli.device, num_envs=args_cli.num_envs, use_fabric=not args_cli.disable_fabric) + agent_cfg = load_cfg_from_registry(args_cli.task, "rl_games_cfg_entry_point") # specify directory for logging experiments diff --git a/scripts/reinforcement_learning/rl_games/train.py b/scripts/reinforcement_learning/rl_games/train.py index e026f5143e4..778114dcedb 100644 --- a/scripts/reinforcement_learning/rl_games/train.py +++ b/scripts/reinforcement_learning/rl_games/train.py @@ -38,7 +38,6 @@ const=True, help="if toggled, this experiment will be tracked with Weights and Biases", ) -parser.add_argument("--viz", action="store_true", default=False, help="Enable visualization for monitoring and debugging.") # append AppLauncher cli args AppLauncher.add_app_launcher_args(parser) # parse the arguments @@ -91,12 +90,6 @@ def main(env_cfg: ManagerBasedRLEnvCfg | DirectRLEnvCfg, agent_cfg: dict): env_cfg.scene.num_envs = args_cli.num_envs if args_cli.num_envs is not None else env_cfg.scene.num_envs env_cfg.sim.device = args_cli.device if args_cli.device is not None else env_cfg.sim.device - # set visualizers based on --viz flag - if not args_cli.viz: - # Explicitly disable visualizers when --viz is not provided - env_cfg.sim.visualizer_cfgs = [] - # else: use the default visualizer_cfgs from the environment config - # randomly sample a seed if seed = -1 if args_cli.seed == -1: args_cli.seed = random.randint(0, 10000) diff --git a/scripts/reinforcement_learning/rsl_rl/play.py b/scripts/reinforcement_learning/rsl_rl/play.py index 0f8f67f1b1f..eea022507cf 100644 --- a/scripts/reinforcement_learning/rsl_rl/play.py +++ b/scripts/reinforcement_learning/rsl_rl/play.py @@ -34,7 +34,6 @@ help="Use the pre-trained checkpoint from Nucleus.", ) parser.add_argument("--real-time", action="store_true", default=False, help="Run in real-time, if possible.") -parser.add_argument("--viz", action="store_true", default=False, help="Enable visualization for monitoring and debugging.") # append RSL-RL cli arguments cli_args.add_rsl_rl_args(parser) # append AppLauncher cli args @@ -97,18 +96,6 @@ def main(env_cfg: ManagerBasedRLEnvCfg | DirectRLEnvCfg, agent_cfg: RslRlBaseRun env_cfg.seed = agent_cfg.seed env_cfg.sim.device = args_cli.device if args_cli.device is not None else env_cfg.sim.device - # set visualizers based on --viz flag - if not args_cli.viz: - env_cfg.sim.visualizer_cfgs = [] - else: - # For play mode, ensure train_mode=False on all visualizers - if env_cfg.sim.visualizer_cfgs is not None: - if isinstance(env_cfg.sim.visualizer_cfgs, list): - for viz_cfg in env_cfg.sim.visualizer_cfgs: - viz_cfg.train_mode = False - else: - env_cfg.sim.visualizer_cfgs.train_mode = False - # specify directory for logging experiments log_root_path = os.path.join("logs", "rsl_rl", agent_cfg.experiment_name) log_root_path = os.path.abspath(log_root_path) diff --git a/scripts/reinforcement_learning/rsl_rl/train.py b/scripts/reinforcement_learning/rsl_rl/train.py index 31b94b42207..b9a80a0ef1b 100644 --- a/scripts/reinforcement_learning/rsl_rl/train.py +++ b/scripts/reinforcement_learning/rsl_rl/train.py @@ -32,7 +32,6 @@ "--distributed", action="store_true", default=False, help="Run training with multiple GPUs or nodes." ) parser.add_argument("--export_io_descriptors", action="store_true", default=False, help="Export IO descriptors.") -parser.add_argument("--viz", action="store_true", default=False, help="Enable visualization for monitoring and debugging") # append RSL-RL cli arguments cli_args.add_rsl_rl_args(parser) # append AppLauncher cli args @@ -120,12 +119,6 @@ def main(env_cfg: ManagerBasedRLEnvCfg | DirectRLEnvCfg, agent_cfg: RslRlBaseRun env_cfg.seed = agent_cfg.seed env_cfg.sim.device = args_cli.device if args_cli.device is not None else env_cfg.sim.device - # set visualizers based on --viz flag - if not args_cli.viz: - # Explicitly disable visualizers when --viz is not provided - env_cfg.sim.visualizer_cfgs = [] - # else: use the default visualizer_cfgs from the environment config - # multi-gpu training configuration if args_cli.distributed: env_cfg.sim.device = f"cuda:{app_launcher.local_rank}" diff --git a/scripts/reinforcement_learning/sb3/play.py b/scripts/reinforcement_learning/sb3/play.py index af3b0ae6ce0..4f29f5b6fc4 100644 --- a/scripts/reinforcement_learning/sb3/play.py +++ b/scripts/reinforcement_learning/sb3/play.py @@ -39,7 +39,6 @@ default=False, help="Use a slower SB3 wrapper but keep all the extra training info.", ) -parser.add_argument("--viz", action="store_true", default=False, help="Enable visualization for monitoring and debugging.") # append AppLauncher cli args AppLauncher.add_app_launcher_args(parser) # parse the arguments @@ -82,7 +81,7 @@ def main(): """Play with stable-baselines agent.""" # parse configuration - env_cfg = parse_env_cfg(args_cli.task, device=args_cli.device, num_envs=args_cli.num_envs, use_fabric=not args_cli.disable_fabric, visualize=args_cli.viz, train_mode=False) + env_cfg = parse_env_cfg(args_cli.task, device=args_cli.device, num_envs=args_cli.num_envs, use_fabric=not args_cli.disable_fabric) task_name = args_cli.task.split(":")[-1] train_task_name = task_name.replace("-Play", "") diff --git a/scripts/reinforcement_learning/sb3/train.py b/scripts/reinforcement_learning/sb3/train.py index 073e316b15c..e86be128439 100644 --- a/scripts/reinforcement_learning/sb3/train.py +++ b/scripts/reinforcement_learning/sb3/train.py @@ -32,7 +32,6 @@ default=False, help="Use a slower SB3 wrapper but keep all the extra training info.", ) -parser.add_argument("--viz", action="store_true", default=False, help="Enable visualization for monitoring and debugging.") # append AppLauncher cli args AppLauncher.add_app_launcher_args(parser) # parse the arguments @@ -114,12 +113,6 @@ def main(env_cfg: ManagerBasedRLEnvCfg | DirectRLEnvCfg, agent_cfg: dict): env_cfg.seed = agent_cfg["seed"] env_cfg.sim.device = args_cli.device if args_cli.device is not None else env_cfg.sim.device - # set visualizers based on --viz flag - if not args_cli.viz: - # Explicitly disable visualizers when --viz is not provided - env_cfg.sim.visualizer_cfgs = [] - # else: use the default visualizer_cfgs from the environment config - # directory for logging into run_info = datetime.now().strftime("%Y-%m-%d_%H-%M-%S") log_root_path = os.path.abspath(os.path.join("logs", "sb3", args_cli.task)) diff --git a/scripts/reinforcement_learning/skrl/play.py b/scripts/reinforcement_learning/skrl/play.py index 6a380a4665c..1a1f7085dc5 100644 --- a/scripts/reinforcement_learning/skrl/play.py +++ b/scripts/reinforcement_learning/skrl/play.py @@ -46,7 +46,6 @@ help="The RL algorithm used for training the skrl agent.", ) parser.add_argument("--real-time", action="store_true", default=False, help="Run in real-time, if possible.") -parser.add_argument("--viz", action="store_true", default=False, help="Enable visualization for monitoring and debugging.") # append AppLauncher cli args AppLauncher.add_app_launcher_args(parser) @@ -111,7 +110,7 @@ def main(): task_name = args_cli.task.split(":")[-1] # parse configuration - env_cfg = parse_env_cfg(args_cli.task, device=args_cli.device, num_envs=args_cli.num_envs, use_fabric=not args_cli.disable_fabric, visualize=args_cli.viz, train_mode=False) + env_cfg = parse_env_cfg(args_cli.task, device=args_cli.device, num_envs=args_cli.num_envs, use_fabric=not args_cli.disable_fabric) try: experiment_cfg = load_cfg_from_registry(task_name, f"skrl_{algorithm}_cfg_entry_point") except ValueError: diff --git a/scripts/reinforcement_learning/skrl/train.py b/scripts/reinforcement_learning/skrl/train.py index bac4b0fe64b..ff01055e344 100644 --- a/scripts/reinforcement_learning/skrl/train.py +++ b/scripts/reinforcement_learning/skrl/train.py @@ -44,7 +44,6 @@ choices=["AMP", "PPO", "IPPO", "MAPPO"], help="The RL algorithm used for training the skrl agent.", ) -parser.add_argument("--viz", action="store_true", default=False, help="Enable visualization for monitoring and debugging.") # append AppLauncher cli args AppLauncher.add_app_launcher_args(parser) @@ -114,12 +113,6 @@ def main(env_cfg: ManagerBasedRLEnvCfg | DirectRLEnvCfg, agent_cfg: dict): env_cfg.scene.num_envs = args_cli.num_envs if args_cli.num_envs is not None else env_cfg.scene.num_envs env_cfg.sim.device = args_cli.device if args_cli.device is not None else env_cfg.sim.device - # set visualizers based on --viz flag - if not args_cli.viz: - # Explicitly disable visualizers when --viz is not provided - env_cfg.sim.visualizer_cfgs = [] - # else: use the default visualizer_cfgs from the environment config - # multi-gpu training config if args_cli.distributed: env_cfg.sim.device = f"cuda:{app_launcher.local_rank}" diff --git a/scripts/sim2sim_transfer/rsl_rl_transfer.py b/scripts/sim2sim_transfer/rsl_rl_transfer.py index 2ce2d4cf42e..aeab61a768d 100644 --- a/scripts/sim2sim_transfer/rsl_rl_transfer.py +++ b/scripts/sim2sim_transfer/rsl_rl_transfer.py @@ -29,7 +29,6 @@ help="Use the pre-trained checkpoint from Nucleus.", ) parser.add_argument("--real-time", action="store_true", default=False, help="Run in real-time, if possible.") -parser.add_argument("--viz", action="store_true", default=False, help="Enable visualization for monitoring and debugging.") # Joint ordering arguments parser.add_argument( "--policy_transfer_file", @@ -149,11 +148,6 @@ def main(): use_fabric=not args_cli.disable_fabric, ) - # set visualizers based on --viz flag - if not args_cli.viz: - # Explicitly disable visualizers when --viz is not provided - env_cfg.sim.visualizer_cfgs = [] - # else: use the default visualizer_cfgs from the environment config agent_cfg: RslRlOnPolicyRunnerCfg = cli_args.parse_rsl_rl_cfg(task_name, args_cli) # specify directory for logging experiments diff --git a/source/isaaclab/isaaclab/sim/scene_data_provider.py b/source/isaaclab/isaaclab/sim/scene_data_provider.py new file mode 100644 index 00000000000..6399d4dca11 --- /dev/null +++ b/source/isaaclab/isaaclab/sim/scene_data_provider.py @@ -0,0 +1,123 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Scene data provider for visualizers and renderers. + +This module provides a unified interface for accessing scene data from different physics backends +and synchronizing that data to rendering backends (USD Fabric, etc.). +""" + +from __future__ import annotations + +from typing import TYPE_CHECKING, Any + +if TYPE_CHECKING: + from newton import Model, State + + +class SceneDataProvider: + """Unified scene data provider for all physics and rendering backends. + + This class provides: + - Access to physics state and model for visualizers (Newton OpenGL, Rerun) + - Synchronization of physics state to USD Fabric for OV visualizer + - Conditional updates based on active visualizers to avoid unnecessary work + + The provider handles both Newton-specific data (state, model) and OV-specific + synchronization (fabric transforms) within a single class to keep the abstraction + simple while supporting multiple backends. + """ + + def __init__(self, visualizer_cfgs: list[Any] | None = None): + """Initialize the scene data provider with visualizer configurations. + + Args: + visualizer_cfgs: List of visualizer configurations to determine which backends are active. + """ + self._has_newton_visualizer = False + self._has_rerun_visualizer = False + self._has_ov_visualizer = False + self._is_initialized = False + + # Determine which visualizers are enabled from configs + if visualizer_cfgs: + for cfg in visualizer_cfgs: + viz_type = getattr(cfg, 'visualizer_type', None) + if viz_type == 'newton': + self._has_newton_visualizer = True + elif viz_type == 'rerun': + self._has_rerun_visualizer = True + elif viz_type == 'omniverse': + self._has_ov_visualizer = True + + self._is_initialized = True + + def update(self) -> None: + """Update scene data for visualizers. + + This method: + - Syncs Newton transforms to USD Fabric (if OV visualizer is active) + - Can be extended for other backend-specific updates + + Note: + Only performs work if necessary visualizers are active to avoid overhead. + """ + if not self._is_initialized: + return + + # Sync fabric transforms only if OV visualizer is active + if self._has_ov_visualizer: + self._sync_fabric_transforms() + + def get_state(self) -> State | None: + """Get physics state for Newton-based visualizers. + + Returns: + Newton State object, or None if not available. + """ + # State is needed by Newton OpenGL and Rerun visualizers + if not (self._has_newton_visualizer or self._has_rerun_visualizer): + return None + + # Lazy import to avoid loading Newton if not needed + try: + from isaaclab.sim._impl.newton_manager import NewtonManager + return NewtonManager._state_0 + except ImportError: + return None + + def get_model(self) -> Model | None: + """Get physics model for Newton-based visualizers. + + Returns: + Newton Model object, or None if not available. + """ + # Model is needed by Newton OpenGL and Rerun visualizers + if not (self._has_newton_visualizer or self._has_rerun_visualizer): + return None + + # Lazy import to avoid loading Newton if not needed + try: + from isaaclab.sim._impl.newton_manager import NewtonManager + return NewtonManager._model + except ImportError: + return None + + def _sync_fabric_transforms(self) -> None: + """Sync Newton transforms to USD Fabric for OV visualizer. + + This method calls NewtonManager.sync_fabric_transforms() to update the + USD Fabric with the latest physics transforms. This allows the OV visualizer + to render the scene without additional data transfer. + + Note: + This is only called when OV visualizer is active to avoid unnecessary GPU work. + """ + try: + from isaaclab.sim._impl.newton_manager import NewtonManager + NewtonManager.sync_fabric_transforms() + except ImportError: + pass + diff --git a/source/isaaclab/isaaclab/sim/simulation_cfg.py b/source/isaaclab/isaaclab/sim/simulation_cfg.py index 5cab905e249..9069b16075d 100644 --- a/source/isaaclab/isaaclab/sim/simulation_cfg.py +++ b/source/isaaclab/isaaclab/sim/simulation_cfg.py @@ -15,7 +15,7 @@ from ._impl.newton_manager_cfg import NewtonCfg from .spawners.materials import RigidBodyMaterialCfg -from .visualizers import VisualizerCfg, NewtonVisualizerCfg, OVVisualizerCfg, RerunVisualizerCfg +from isaaclab.visualizers import VisualizerCfg, NewtonVisualizerCfg, OVVisualizerCfg, RerunVisualizerCfg @configclass @@ -219,13 +219,13 @@ class SimulationCfg: cfg = SimulationCfg() # Single custom visualizer - from isaaclab.sim.visualizers import OVVisualizerCfg + from isaaclab.visualizers import OVVisualizerCfg cfg = SimulationCfg(visualizer_cfgs=OVVisualizerCfg()) # Multiple visualizers with custom configuration - from isaaclab.sim.visualizers import NewtonVisualizerCfg, RerunVisualizerCfg + from isaaclab.visualizers import NewtonVisualizerCfg, RerunVisualizerCfg cfg = SimulationCfg(visualizer_cfgs=[ - NewtonVisualizerCfg(env_ids_to_viz=[0], camera_position=(10.0, 0.0, 3.0)), + NewtonVisualizerCfg(camera_position=(10.0, 0.0, 3.0)), RerunVisualizerCfg(server_address="127.0.0.1:9876") ]) diff --git a/source/isaaclab/isaaclab/sim/simulation_context.py b/source/isaaclab/isaaclab/sim/simulation_context.py index 3c2eaaaf80a..05a2f0e6fa8 100644 --- a/source/isaaclab/isaaclab/sim/simulation_context.py +++ b/source/isaaclab/isaaclab/sim/simulation_context.py @@ -33,9 +33,10 @@ from isaaclab.sim.utils import create_new_stage_in_memory, use_stage from .simulation_cfg import SimulationCfg +from .scene_data_provider import SceneDataProvider from .spawners import DomeLightCfg, GroundPlaneCfg from .utils import bind_physics_material -from .visualizers import Visualizer +from isaaclab.visualizers import Visualizer class SimulationContext(_SimulationContext): @@ -253,9 +254,10 @@ def __init__(self, cfg: SimulationCfg | None = None): self._app_control_on_stop_handle = None self._disable_app_control_on_stop_handle = False - # initialize visualizers + # initialize visualizers and scene data provider self._visualizers: list[Visualizer] = [] self._visualizer_step_counter = 0 + self._scene_data_provider: SceneDataProvider | None = None # flag for skipping prim deletion callback # when stage in memory is attached self._skip_next_prim_deletion_callback_fn = False @@ -538,9 +540,11 @@ def get_setting(self, name: str) -> Any: return self._settings.get(name) def forward(self) -> None: - """Updates articulation kinematics and fabric for rendering.""" + """Updates articulation kinematics and scene data for rendering.""" NewtonManager.forward_kinematics() - NewtonManager.sync_fabric_transforms() + # Update scene data provider (syncs fabric transforms if needed) + if self._scene_data_provider: + self._scene_data_provider.update() def initialize_visualizers(self) -> None: """Initialize all configured visualizers. @@ -550,7 +554,14 @@ def initialize_visualizers(self) -> None: - A single VisualizerCfg: Creates one visualizer - A list of VisualizerCfg: Creates multiple visualizers - None or empty list: No visualizers are created + + Note: + Visualizers are automatically skipped when running in headless mode. """ + # Skip visualizers in headless mode + if not self._has_gui and not self._offscreen_render: + return + # Handle different input formats visualizer_cfgs = [] if self.cfg.visualizer_cfgs is not None: @@ -559,15 +570,21 @@ def initialize_visualizers(self) -> None: else: visualizer_cfgs = [self.cfg.visualizer_cfgs] + # Create scene data provider with visualizer configs + # Provider will determine which backends are active + if visualizer_cfgs: + self._scene_data_provider = SceneDataProvider(visualizer_cfgs) + # Create and initialize each visualizer for viz_cfg in visualizer_cfgs: try: visualizer = viz_cfg.create_visualizer() - # Pass minimal generic scene data - visualizers fetch backend-specific data themselves + # Pass scene data including provider scene_data = { "simulation_context": self, "usd_stage": self.stage, + "scene_data_provider": self._scene_data_provider, } # Initialize visualizer with scene data @@ -1030,7 +1047,7 @@ def enable_visualizers(env_cfg, train_mode: bool = True) -> None: >>> if args_cli.visualize: ... sim_utils.enable_visualizers(env_cfg) """ - from isaaclab.sim.visualizers import NewtonVisualizerCfg + from isaaclab.visualizers import NewtonVisualizerCfg if env_cfg.sim.visualizer_cfgs is None: env_cfg.sim.visualizer_cfgs = NewtonVisualizerCfg() diff --git a/source/isaaclab/isaaclab/sim/visualizers/__init__.py b/source/isaaclab/isaaclab/visualizers/__init__.py similarity index 100% rename from source/isaaclab/isaaclab/sim/visualizers/__init__.py rename to source/isaaclab/isaaclab/visualizers/__init__.py diff --git a/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py b/source/isaaclab/isaaclab/visualizers/newton_visualizer.py similarity index 81% rename from source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py rename to source/isaaclab/isaaclab/visualizers/newton_visualizer.py index 0c3ddf83b29..bee4779975d 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer.py +++ b/source/isaaclab/isaaclab/visualizers/newton_visualizer.py @@ -25,11 +25,10 @@ class NewtonViewerGL(ViewerGL): - Rendering pause: Stops rendering updates, continues physics (SPACE key) """ - def __init__(self, *args, train_mode: bool = True, metadata: dict | None = None, update_frequency: int = 1, **kwargs): + def __init__(self, *args, metadata: dict | None = None, update_frequency: int = 1, **kwargs): super().__init__(*args, **kwargs) self._paused_training = False self._paused_rendering = False - self._is_train_mode = train_mode self._metadata = metadata or {} self._fallback_draw_controls = False self._update_frequency = update_frequency @@ -51,22 +50,18 @@ def is_paused(self) -> bool: def _render_training_controls(self, imgui): imgui.separator() + imgui.text("IsaacLab Controls") - if self._is_train_mode: - imgui.text("IsaacLab Training Controls") - pause_label = "Resume Training" if self._paused_training else "Pause Training" - else: - imgui.text("IsaacLab Playback Controls") - pause_label = "Resume Playing" if self._paused_training else "Pause Playing" - + # Pause training/simulation button + pause_label = "Resume Training" if self._paused_training else "Pause Training" if imgui.button(pause_label): self._paused_training = not self._paused_training - if self._is_train_mode: - rendering_label = "Resume Rendering" if self._paused_rendering else "Pause Rendering" - if imgui.button(rendering_label): - self._paused_rendering = not self._paused_rendering - self._paused = self._paused_rendering + # Pause rendering button + rendering_label = "Resume Rendering" if self._paused_rendering else "Pause Rendering" + if imgui.button(rendering_label): + self._paused_rendering = not self._paused_rendering + self._paused = self._paused_rendering # Visualizer update frequency control imgui.text("Visualizer Update Frequency") @@ -251,17 +246,28 @@ def __init__(self, cfg: NewtonVisualizerCfg): self._model = None self._state = None self._update_frequency = cfg.update_frequency + self._scene_data_provider = None def initialize(self, scene_data: dict[str, Any] | None = None) -> None: """Initialize visualizer with scene data.""" if self._is_initialized: return - # Fetch Newton-specific data from NewtonManager + # Import NewtonManager for metadata access from isaaclab.sim._impl.newton_manager import NewtonManager - self._model = NewtonManager._model - self._state = NewtonManager._state_0 + # Store scene data provider for accessing physics state + if scene_data and "scene_data_provider" in scene_data: + self._scene_data_provider = scene_data["scene_data_provider"] + + # Get Newton-specific data from scene data provider + if self._scene_data_provider: + self._model = self._scene_data_provider.get_model() + self._state = self._scene_data_provider.get_state() + else: + # Fallback: direct access to NewtonManager (for backward compatibility) + self._model = NewtonManager._model + self._state = NewtonManager._state_0 if self._model is None: raise RuntimeError( @@ -277,11 +283,10 @@ def initialize(self, scene_data: dict[str, Any] | None = None) -> None: "clone_physics_only": NewtonManager._clone_physics_only, } - # Create the viewer with train_mode and metadata + # Create the viewer with metadata self._viewer = NewtonViewerGL( width=self.cfg.window_width, height=self.cfg.window_height, - train_mode=self.cfg.train_mode, metadata=metadata, update_frequency=self.cfg.update_frequency, ) @@ -311,13 +316,7 @@ def initialize(self, scene_data: dict[str, Any] | None = None) -> None: self._viewer.renderer.sky_lower = self.cfg.ground_color self._viewer.renderer._light_color = self.cfg.light_color - # Setup partial visualization (env_ids_to_viz filtering) - if self.cfg.env_ids_to_viz is not None: - num_envs = metadata.get("num_envs", 0) - self._setup_env_filtering(num_envs) - omni.log.info( - f"[NewtonVisualizer] Partial visualization: {len(self.cfg.env_ids_to_viz)}/{num_envs} environments" - ) + # TODO: Partial visualization will be implemented through a new cloner feature self._is_initialized = True @@ -329,9 +328,13 @@ def step(self, dt: float, state: Any | None = None) -> None: self._sim_time += dt self._step_counter += 1 - # Fetch updated state from NewtonManager - from isaaclab.sim._impl.newton_manager import NewtonManager - self._state = NewtonManager._state_0 + # Fetch updated state from scene data provider + if self._scene_data_provider: + self._state = self._scene_data_provider.get_state() + else: + # Fallback: direct access to NewtonManager + from isaaclab.sim._impl.newton_manager import NewtonManager + self._state = NewtonManager._state_0 # Only update visualizer at the specified frequency update_frequency = self._viewer._update_frequency if self._viewer else self._update_frequency @@ -383,34 +386,4 @@ def is_rendering_paused(self) -> bool: return False return self._viewer.is_rendering_paused() - def _setup_env_filtering(self, num_envs: int) -> None: - """Setup environment filtering using world offsets. - - NOTE: This uses visualization-only offsets that do NOT affect physics simulation. - Newton's world_offsets only shift the rendered position of environments, not their - physical positions. This is confirmed by Newton's test_visual_separation test. - - Current approach: Moves non-visualized environments far away (10000 units) to hide them. - This works but is not ideal. Future improvements could include: - - Proper culling at the viewer level - - Selective state logging (only log visualized envs) - - Custom rendering callbacks - - Args: - num_envs: Total number of environments. - """ - import warp as wp - - # Create world offsets array (use viewer's device, not renderer's) - offsets = wp.zeros(num_envs, dtype=wp.vec3, device=self._viewer.device) - offsets_np = offsets.numpy() - - # Move non-visualized environments far away (visualization-only, doesn't affect physics) - visualized_set = set(self.cfg.env_ids_to_viz) - for world_idx in range(num_envs): - if world_idx not in visualized_set: - offsets_np[world_idx] = (10000.0, 10000.0, 10000.0) - - offsets.assign(offsets_np) - self._viewer.world_offsets = offsets diff --git a/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer_cfg.py b/source/isaaclab/isaaclab/visualizers/newton_visualizer_cfg.py similarity index 94% rename from source/isaaclab/isaaclab/sim/visualizers/newton_visualizer_cfg.py rename to source/isaaclab/isaaclab/visualizers/newton_visualizer_cfg.py index bd571741cf2..98544d5f549 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/newton_visualizer_cfg.py +++ b/source/isaaclab/isaaclab/visualizers/newton_visualizer_cfg.py @@ -37,9 +37,6 @@ class NewtonVisualizerCfg(VisualizerCfg): camera_target: tuple[float, float, float] = (0.0, 0.0, 0.0) """Initial camera target/look-at point (x, y, z).""" - train_mode: bool = True - """Training mode (True) shows rendering pause controls, play mode (False) hides them.""" - update_frequency: int = 1 """Visualizer update frequency (updates every N frames). Lower = more responsive but slower training.""" diff --git a/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer.py b/source/isaaclab/isaaclab/visualizers/ov_visualizer.py similarity index 87% rename from source/isaaclab/isaaclab/sim/visualizers/ov_visualizer.py rename to source/isaaclab/isaaclab/visualizers/ov_visualizer.py index 9247f5a6758..451120c6b34 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer.py +++ b/source/isaaclab/isaaclab/visualizers/ov_visualizer.py @@ -69,14 +69,11 @@ def initialize(self, scene_data: dict[str, Any] | None = None) -> None: self._ensure_simulation_app() self._setup_viewport(usd_stage, metadata) - # Setup partial visualization (env_ids_to_viz filtering) - num_envs = metadata.get("num_envs", 0) - if self.cfg.env_ids_to_viz is not None: - self._setup_env_filtering(usd_stage, metadata, num_envs) + # TODO: Partial visualization will be implemented through a new cloner feature + num_envs = metadata.get("num_envs", 0) physics_backend = metadata.get("physics_backend", "unknown") - viz_envs = len(self.cfg.env_ids_to_viz) if self.cfg.env_ids_to_viz else num_envs - omni.log.info(f"[OVVisualizer] Initialized ({viz_envs}/{num_envs} envs, {physics_backend} physics)") + omni.log.info(f"[OVVisualizer] Initialized ({num_envs} envs, {physics_backend} physics)") self._is_initialized = True @@ -367,46 +364,3 @@ def _set_viewport_camera( except Exception as e: omni.log.warn(f"[OVVisualizer] Could not set camera: {e}") - def _setup_env_filtering(self, usd_stage, metadata: dict, num_envs: int) -> None: - """Setup environment filtering by hiding non-visualized environment prims. - - WIP: Sets USD visibility to 'invisible' for non-visualized environments. - Future: Could use more sophisticated culling or instancing techniques. - - Args: - usd_stage: The USD stage. - metadata: Scene metadata containing environment prim paths. - num_envs: Total number of environments. - """ - try: - from pxr import UsdGeom - - # Get environment prim pattern from metadata - # Default pattern assumes envs are at /World/envs/env_* - env_prim_pattern = metadata.get("env_prim_pattern", "/World/envs/env_{}") - - visualized_set = set(self.cfg.env_ids_to_viz) - hidden_count = 0 - - for env_idx in range(num_envs): - if env_idx not in visualized_set: - # Format the environment prim path - env_path = env_prim_pattern.format(env_idx) - prim = usd_stage.GetPrimAtPath(env_path) - - if prim.IsValid(): - # Make the prim invisible - imageable = UsdGeom.Imageable(prim) - if imageable: - imageable.MakeInvisible() - hidden_count += 1 - else: - omni.log.warn(f"[OVVisualizer] Environment prim not found: {env_path}") - - omni.log.info( - f"[OVVisualizer] Partial visualization enabled: " - f"hidden {hidden_count} environments, showing {len(self.cfg.env_ids_to_viz)}/{num_envs}" - ) - - except Exception as e: - omni.log.warn(f"[OVVisualizer] Failed to setup environment filtering: {e}") diff --git a/source/isaaclab/isaaclab/sim/visualizers/ov_visualizer_cfg.py b/source/isaaclab/isaaclab/visualizers/ov_visualizer_cfg.py similarity index 100% rename from source/isaaclab/isaaclab/sim/visualizers/ov_visualizer_cfg.py rename to source/isaaclab/isaaclab/visualizers/ov_visualizer_cfg.py diff --git a/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer.py b/source/isaaclab/isaaclab/visualizers/rerun_visualizer.py similarity index 85% rename from source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer.py rename to source/isaaclab/isaaclab/visualizers/rerun_visualizer.py index 829b1127709..6190d3ef7f1 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer.py +++ b/source/isaaclab/isaaclab/visualizers/rerun_visualizer.py @@ -46,12 +46,8 @@ def __init__( metadata: dict | None = None, enable_markers: bool = True, enable_live_plots: bool = True, - env_ids_to_viz: list[int] | None = None, ): """Initialize Newton ViewerRerun wrapper.""" - if not _RERUN_AVAILABLE: - raise ImportError("Rerun visualizer requires rerun-sdk and Newton. Install: pip install rerun-sdk") - # Call parent with only Newton parameters super().__init__( server=server, @@ -67,7 +63,6 @@ def __init__( self._metadata = metadata or {} self._enable_markers = enable_markers self._enable_live_plots = enable_live_plots - self._env_ids_to_viz = env_ids_to_viz # Storage for registered markers and plots self._registered_markers = [] @@ -88,11 +83,6 @@ def _log_metadata(self) -> None: num_envs = self._metadata.get("num_envs", 0) metadata_text += f"**Total Environments:** {num_envs}\n" - if self._env_ids_to_viz is not None: - metadata_text += f"**Visualized Environments:** {len(self._env_ids_to_viz)} (IDs: {self._env_ids_to_viz[:5]}...)\n" - else: - metadata_text += f"**Visualized Environments:** All ({num_envs})\n" - # Physics backend info physics_backend = self._metadata.get("physics_backend", "unknown") metadata_text += f"**Physics:** {physics_backend}\n" @@ -266,6 +256,7 @@ def __init__(self, cfg: RerunVisualizerCfg): self._state = None self._is_initialized = False self._sim_time = 0.0 + self._scene_data_provider = None def initialize(self, scene_data: dict[str, Any] | None = None) -> None: """Initialize visualizer with Newton Model and State.""" @@ -273,11 +264,21 @@ def initialize(self, scene_data: dict[str, Any] | None = None) -> None: omni.log.warn("[RerunVisualizer] Already initialized. Skipping re-initialization.") return - # Fetch Newton-specific data from NewtonManager + # Import NewtonManager for metadata access from isaaclab.sim._impl.newton_manager import NewtonManager - self._model = NewtonManager._model - self._state = NewtonManager._state_0 + # Store scene data provider for accessing physics state + if scene_data and "scene_data_provider" in scene_data: + self._scene_data_provider = scene_data["scene_data_provider"] + + # Get Newton-specific data from scene data provider + if self._scene_data_provider: + self._model = self._scene_data_provider.get_model() + self._state = self._scene_data_provider.get_state() + else: + # Fallback: direct access to NewtonManager (for backward compatibility) + self._model = NewtonManager._model + self._state = NewtonManager._state_0 # Validate required Newton data if self._model is None: @@ -316,22 +317,18 @@ def initialize(self, scene_data: dict[str, Any] | None = None) -> None: metadata=metadata, enable_markers=self.cfg.enable_markers, enable_live_plots=self.cfg.enable_live_plots, - env_ids_to_viz=self.cfg.env_ids_to_viz, ) # Set the model self._viewer.set_model(self._model) - # Setup partial visualization (env_ids_to_viz filtering) - num_envs = metadata.get("num_envs", 0) - if self.cfg.env_ids_to_viz is not None: - self._setup_env_filtering(num_envs) + # TODO: Partial visualization will be implemented through a new cloner feature # Log initialization - viz_envs = len(self.cfg.env_ids_to_viz) if self.cfg.env_ids_to_viz else num_envs + num_envs = metadata.get("num_envs", 0) physics_backend = metadata.get("physics_backend", "newton") omni.log.info( - f"[RerunVisualizer] Initialized with {viz_envs}/{num_envs} environments " + f"[RerunVisualizer] Initialized with {num_envs} environments " f"(physics: {physics_backend})" ) @@ -350,23 +347,21 @@ def step(self, dt: float, state: Any | None = None) -> None: 3. Actively logs markers (if enabled) 4. Actively logs plot data (if enabled) - Implementation Note: - Partial visualization (env_ids_to_viz) is handled internally by filtering - which instance transforms are logged. We log all meshes once (they're - shared assets), but only log transforms for selected environments. - Args: dt: Time step in seconds. state: Unused (deprecated parameter, kept for API compatibility). - """e - + """ if not self._is_initialized or self._viewer is None: omni.log.warn("[RerunVisualizer] Not initialized. Call initialize() first.") return - # Fetch updated state from NewtonManager - from isaaclab.sim._impl.newton_manager import NewtonManager - self._state = NewtonManager._state_0 + # Fetch updated state from scene data provider + if self._scene_data_provider: + self._state = self._scene_data_provider.get_state() + else: + # Fallback: direct access to NewtonManager + from isaaclab.sim._impl.newton_manager import NewtonManager + self._state = NewtonManager._state_0 # Update internal time self._sim_time += dt @@ -468,39 +463,4 @@ def register_plots(self, plots: dict[str, Any]) -> None: if self._viewer: self._viewer.register_plots(plots) - def _setup_env_filtering(self, num_envs: int) -> None: - """Setup environment filtering using world offsets. - - NOTE: This uses visualization-only offsets that do NOT affect physics simulation. - Newton's world_offsets only shift the rendered/logged position of environments, not their - physical positions. This is confirmed by Newton's test_visual_separation test. - - Current approach: Moves non-visualized environments far away (10000 units) to hide them. - This works but is not ideal. Future improvements could include: - - Proper filtering at the logging level (only log selected env transforms) - - Custom logging callbacks for partial visualization - - State slicing before logging - - Args: - num_envs: Total number of environments. - """ - import warp as wp - - # Create world offsets array - offsets = wp.zeros(num_envs, dtype=wp.vec3, device=self._viewer.device) - offsets_np = offsets.numpy() - - # Move non-visualized environments far away (visualization-only, doesn't affect physics) - visualized_set = set(self.cfg.env_ids_to_viz) - for world_idx in range(num_envs): - if world_idx not in visualized_set: - offsets_np[world_idx] = (10000.0, 10000.0, 10000.0) - - offsets.assign(offsets_np) - self._viewer.world_offsets = offsets - - omni.log.info( - f"[RerunVisualizer] Partial visualization enabled: " - f"{len(self.cfg.env_ids_to_viz)}/{num_envs} environments" - ) diff --git a/source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer_cfg.py b/source/isaaclab/isaaclab/visualizers/rerun_visualizer_cfg.py similarity index 100% rename from source/isaaclab/isaaclab/sim/visualizers/rerun_visualizer_cfg.py rename to source/isaaclab/isaaclab/visualizers/rerun_visualizer_cfg.py diff --git a/source/isaaclab/isaaclab/sim/visualizers/visualizer.py b/source/isaaclab/isaaclab/visualizers/visualizer.py similarity index 100% rename from source/isaaclab/isaaclab/sim/visualizers/visualizer.py rename to source/isaaclab/isaaclab/visualizers/visualizer.py diff --git a/source/isaaclab/isaaclab/sim/visualizers/visualizer_cfg.py b/source/isaaclab/isaaclab/visualizers/visualizer_cfg.py similarity index 87% rename from source/isaaclab/isaaclab/sim/visualizers/visualizer_cfg.py rename to source/isaaclab/isaaclab/visualizers/visualizer_cfg.py index df511499804..33822a2bcee 100644 --- a/source/isaaclab/isaaclab/sim/visualizers/visualizer_cfg.py +++ b/source/isaaclab/isaaclab/visualizers/visualizer_cfg.py @@ -22,8 +22,9 @@ class VisualizerCfg: visualizer_type: str = "base" """Type identifier (e.g., 'newton', 'rerun', 'omniverse').""" - env_ids_to_viz: list[int] | None = None - """Environment IDs to visualize. None = all environments.""" + # TODO: Partial visualization will be implemented through a new cloner feature + # that allows filtering environments at the simulation level rather than per-visualizer. + # This approach will be more efficient and consistent across all visualizers. enable_markers: bool = True """Enable visualization markers (debug drawing).""" diff --git a/source/isaaclab/setup.py b/source/isaaclab/setup.py index 82299d1ffc9..d12b156a505 100644 --- a/source/isaaclab/setup.py +++ b/source/isaaclab/setup.py @@ -54,6 +54,8 @@ # "newton @ git+https://github.com/newton-physics/newton.git@c4baa06c3e8ea0a3090037b2b197e9aa453265f1", "imgui-bundle==1.92.0", "PyOpenGL-accelerate==3.1.10", + # visualizers + "rerun-sdk", ] # Additional dependencies that are only available on Linux platforms diff --git a/source/isaaclab_tasks/isaaclab_tasks/utils/parse_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/utils/parse_cfg.py index b8f3357e7ea..212640e1918 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/utils/parse_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/utils/parse_cfg.py @@ -119,8 +119,6 @@ def parse_env_cfg( device: str = "cuda:0", num_envs: int | None = None, use_fabric: bool | None = None, - visualize: bool = False, - train_mode: bool = True, ) -> ManagerBasedRLEnvCfg | DirectRLEnvCfg: """Parse configuration for an environment and override based on inputs. @@ -131,10 +129,6 @@ def parse_env_cfg( use_fabric: Whether to enable/disable fabric interface. If false, all read/write operations go through USD. This slows down the simulation but allows seeing the changes in the USD through the USD stage. Defaults to None, in which case it is left unchanged. - visualize: Whether to launch visualizer(s). Uses visualizers defined in environment config, or defaults - to Newton OpenGL if none configured. Defaults to False. - train_mode: Whether to run visualizers in training mode (True) or play/inference mode (False). - Only applies if visualize is True. Defaults to True. Returns: The parsed configuration object. @@ -142,6 +136,10 @@ def parse_env_cfg( Raises: RuntimeError: If the configuration for the task is not a class. We assume users always use a class for the environment configuration. + + Note: + Visualizer configuration should be done via Hydra command line arguments. + Example: ``env.sim.visualizer_cfgs=isaaclab.visualizers:NewtonVisualizerCfg`` """ # load the default configuration cfg = load_cfg_from_registry(task_name.split(":")[-1], "env_cfg_entry_point") @@ -159,10 +157,6 @@ def parse_env_cfg( # number of environments if num_envs is not None: cfg.scene.num_envs = num_envs - # visualizer configuration - if visualize: - import isaaclab.sim as sim_utils - sim_utils.enable_visualizers(cfg, train_mode=train_mode) return cfg From e4aceabdce65265e07e399a03dec00f72267005b Mon Sep 17 00:00:00 2001 From: mtrepte Date: Fri, 21 Nov 2025 10:52:31 -0800 Subject: [PATCH 18/24] wip --- .../isaaclab/sim/_impl/newton_manager.py | 34 --------- .../isaaclab/sim/scene_data_provider.py | 70 +++++++++++++++++-- .../isaaclab/isaaclab/sim/simulation_cfg.py | 3 +- 3 files changed, 66 insertions(+), 41 deletions(-) diff --git a/source/isaaclab/isaaclab/sim/_impl/newton_manager.py b/source/isaaclab/isaaclab/sim/_impl/newton_manager.py index fb770d6aff3..8ba5777314e 100644 --- a/source/isaaclab/isaaclab/sim/_impl/newton_manager.py +++ b/source/isaaclab/isaaclab/sim/_impl/newton_manager.py @@ -34,18 +34,6 @@ def flipped_match(x: str, y: str) -> re.Match | None: return re.match(y, x) -@wp.kernel(enable_backward=False) -def set_vec3d_array( - fabric_vals: wp.fabricarray(dtype=wp.mat44d), - indices: wp.fabricarray(dtype=wp.uint32), - newton_vals: wp.array(ndim=1, dtype=wp.transformf), -): - i = int(wp.tid()) - idx = int(indices[i]) - new_val = newton_vals[idx] - fabric_vals[i] = wp.transpose(wp.mat44d(wp.math.transform_to_matrix(new_val))) - - class NewtonManager: _builder: ModelBuilder = None _model: Model = None @@ -292,28 +280,6 @@ def set_simulation_dt(cls, dt: float) -> None: """ NewtonManager._dt = dt - @classmethod - def sync_fabric_transforms(cls) -> None: - """Syncs the fabric transforms with the Newton state. - - This function syncs the fabric transforms with the Newton state. - """ - selection = NewtonManager._usdrt_stage.SelectPrims( - require_attrs=[ - (usdrt.Sdf.ValueTypeNames.Matrix4d, "omni:fabric:worldMatrix", usdrt.Usd.Access.ReadWrite), - (usdrt.Sdf.ValueTypeNames.UInt, NewtonManager._newton_index_attr, usdrt.Usd.Access.Read), - ], - device="cuda:0", - ) - fabric_newton_indices = wp.fabricarray(selection, NewtonManager._newton_index_attr) - current_transforms = wp.fabricarray(selection, "omni:fabric:worldMatrix") - wp.launch( - set_vec3d_array, - dim=(fabric_newton_indices.shape[0]), - inputs=[current_transforms, fabric_newton_indices, NewtonManager._state_0.body_q], - device="cuda:0", - ) - @classmethod def get_model(cls): return NewtonManager._model diff --git a/source/isaaclab/isaaclab/sim/scene_data_provider.py b/source/isaaclab/isaaclab/sim/scene_data_provider.py index 6399d4dca11..ac7c46f119f 100644 --- a/source/isaaclab/isaaclab/sim/scene_data_provider.py +++ b/source/isaaclab/isaaclab/sim/scene_data_provider.py @@ -17,6 +17,33 @@ from newton import Model, State +# Lazy import warp dependencies for OV visualizer support +def _get_warp_kernel(): + """Get the warp kernel for syncing fabric transforms. + + Returns the kernel only when warp is available, avoiding import errors + when warp is not installed. + """ + try: + import warp as wp + + # Define warp kernel for syncing transforms + @wp.kernel(enable_backward=False) + def set_vec3d_array( + fabric_vals: wp.fabricarray(dtype=wp.mat44d), + indices: wp.fabricarray(dtype=wp.uint32), + newton_vals: wp.array(ndim=1, dtype=wp.transformf), + ): + i = int(wp.tid()) + idx = int(indices[i]) + new_val = newton_vals[idx] + fabric_vals[i] = wp.transpose(wp.mat44d(wp.math.transform_to_matrix(new_val))) + + return set_vec3d_array + except ImportError: + return None + + class SceneDataProvider: """Unified scene data provider for all physics and rendering backends. @@ -108,16 +135,47 @@ def get_model(self) -> Model | None: def _sync_fabric_transforms(self) -> None: """Sync Newton transforms to USD Fabric for OV visualizer. - This method calls NewtonManager.sync_fabric_transforms() to update the - USD Fabric with the latest physics transforms. This allows the OV visualizer - to render the scene without additional data transfer. + This method updates the USD Fabric with the latest physics transforms from Newton. + It uses a warp kernel to efficiently copy transform data on the GPU. + + The sync process: + 1. Selects USD prims that have both worldMatrix and newton index attributes + 2. Creates fabric arrays for transforms and indices + 3. Launches warp kernel to copy Newton body transforms to USD Fabric Note: This is only called when OV visualizer is active to avoid unnecessary GPU work. """ + # Get warp kernel (lazy loaded) + set_vec3d_array = _get_warp_kernel() + if set_vec3d_array is None: + return + try: + import usdrt + import warp as wp from isaaclab.sim._impl.newton_manager import NewtonManager - NewtonManager.sync_fabric_transforms() - except ImportError: + + # Select all prims with required attributes + selection = NewtonManager._usdrt_stage.SelectPrims( + require_attrs=[ + (usdrt.Sdf.ValueTypeNames.Matrix4d, "omni:fabric:worldMatrix", usdrt.Usd.Access.ReadWrite), + (usdrt.Sdf.ValueTypeNames.UInt, NewtonManager._newton_index_attr, usdrt.Usd.Access.Read), + ], + device="cuda:0", + ) + + # Create fabric arrays for indices and transforms + fabric_newton_indices = wp.fabricarray(selection, NewtonManager._newton_index_attr) + current_transforms = wp.fabricarray(selection, "omni:fabric:worldMatrix") + + # Launch warp kernel to sync transforms + wp.launch( + set_vec3d_array, + dim=(fabric_newton_indices.shape[0]), + inputs=[current_transforms, fabric_newton_indices, NewtonManager._state_0.body_q], + device="cuda:0", + ) + except (ImportError, AttributeError): + # Silently fail if Newton isn't initialized or attributes are missing pass - diff --git a/source/isaaclab/isaaclab/sim/simulation_cfg.py b/source/isaaclab/isaaclab/sim/simulation_cfg.py index 9069b16075d..06139132f01 100644 --- a/source/isaaclab/isaaclab/sim/simulation_cfg.py +++ b/source/isaaclab/isaaclab/sim/simulation_cfg.py @@ -197,7 +197,8 @@ class SimulationCfg: render_cfg: RenderCfg = RenderCfg() """Render settings. Default is RenderCfg().""" - visualizer_cfgs: list[VisualizerCfg] | VisualizerCfg | None = NewtonVisualizerCfg() + # visualizer_cfgs: list[VisualizerCfg] | VisualizerCfg | None = NewtonVisualizerCfg() + visualizer_cfgs: list[VisualizerCfg] | VisualizerCfg | None = [OVVisualizerCfg(), NewtonVisualizerCfg()] """Visualizer settings. Default is NewtonVisualizerCfg(). This field supports multiple visualizer backends for debug visualization and monitoring From 0f99eaad66e2e8c2f4ca949de1977348f2090907 Mon Sep 17 00:00:00 2001 From: mtrepte Date: Fri, 21 Nov 2025 11:03:00 -0800 Subject: [PATCH 19/24] clean --- .../isaaclab/sim/simulation_context.py | 19 ++++++++++++------- 1 file changed, 12 insertions(+), 7 deletions(-) diff --git a/source/isaaclab/isaaclab/sim/simulation_context.py b/source/isaaclab/isaaclab/sim/simulation_context.py index 05a2f0e6fa8..2fa7259aa03 100644 --- a/source/isaaclab/isaaclab/sim/simulation_context.py +++ b/source/isaaclab/isaaclab/sim/simulation_context.py @@ -580,14 +580,19 @@ def initialize_visualizers(self) -> None: try: visualizer = viz_cfg.create_visualizer() - # Pass scene data including provider - scene_data = { - "simulation_context": self, - "usd_stage": self.stage, - "scene_data_provider": self._scene_data_provider, - } + # Build scene data dict with only what this visualizer needs + scene_data = {} - # Initialize visualizer with scene data + # Newton and Rerun visualizers only need scene_data_provider + if viz_cfg.visualizer_type in ("newton", "rerun"): + scene_data["scene_data_provider"] = self._scene_data_provider + + # OV visualizer needs USD stage and simulation context + elif viz_cfg.visualizer_type == "omniverse": + scene_data["usd_stage"] = self.stage + scene_data["simulation_context"] = self + + # Initialize visualizer with minimal required data visualizer.initialize(scene_data) self._visualizers.append(visualizer) omni.log.info( From a5f8256d8402acd3d6869450ca9bbd5e7d3d6746 Mon Sep 17 00:00:00 2001 From: mtrepte Date: Fri, 21 Nov 2025 15:19:41 -0800 Subject: [PATCH 20/24] prepare for merge; --- scripts/environments/random_agent.py | 2 +- scripts/environments/zero_agent.py | 2 +- .../reinforcement_learning/rl_games/play.py | 6 +- scripts/reinforcement_learning/sb3/play.py | 4 +- scripts/reinforcement_learning/skrl/play.py | 4 +- scripts/sim2sim_transfer/rsl_rl_transfer.py | 2 +- .../isaaclab/envs/ui/base_env_window.py | 16 +- .../isaaclab/sim/_impl/newton_manager.py | 1 - .../isaaclab/sim/scene_data_provider.py | 63 ++-- .../isaaclab/isaaclab/sim/simulation_cfg.py | 24 +- .../isaaclab/sim/simulation_context.py | 53 ++- .../isaaclab/isaaclab/visualizers/__init__.py | 27 +- .../isaaclab/visualizers/newton_visualizer.py | 52 ++- .../visualizers/newton_visualizer_cfg.py | 4 +- .../isaaclab/visualizers/ov_visualizer.py | 193 ++++++----- .../isaaclab/visualizers/ov_visualizer_cfg.py | 25 +- .../isaaclab/visualizers/rerun_visualizer.py | 318 ++++-------------- .../visualizers/rerun_visualizer_cfg.py | 8 +- .../isaaclab/visualizers/visualizer.py | 9 +- .../isaaclab/visualizers/visualizer_cfg.py | 15 +- source/isaaclab/setup.py | 6 +- .../isaaclab_tasks/utils/parse_cfg.py | 2 +- 22 files changed, 319 insertions(+), 517 deletions(-) diff --git a/scripts/environments/random_agent.py b/scripts/environments/random_agent.py index c7d584ef924..6ecce8de74d 100644 --- a/scripts/environments/random_agent.py +++ b/scripts/environments/random_agent.py @@ -52,7 +52,7 @@ def main(): num_envs=args_cli.num_envs, use_fabric=not args_cli.disable_fabric, ) - + # create environment env = gym.make(args_cli.task, cfg=env_cfg) diff --git a/scripts/environments/zero_agent.py b/scripts/environments/zero_agent.py index 50017af4ba9..bdca64d515e 100644 --- a/scripts/environments/zero_agent.py +++ b/scripts/environments/zero_agent.py @@ -52,7 +52,7 @@ def main(): num_envs=args_cli.num_envs, use_fabric=not args_cli.disable_fabric, ) - + # create environment env = gym.make(args_cli.task, cfg=env_cfg) diff --git a/scripts/reinforcement_learning/rl_games/play.py b/scripts/reinforcement_learning/rl_games/play.py index 6ce539a55c0..a80329c2757 100644 --- a/scripts/reinforcement_learning/rl_games/play.py +++ b/scripts/reinforcement_learning/rl_games/play.py @@ -78,8 +78,10 @@ def main(): """Play with RL-Games agent.""" task_name = args_cli.task.split(":")[-1] # parse env configuration - env_cfg = parse_env_cfg(args_cli.task, device=args_cli.device, num_envs=args_cli.num_envs, use_fabric=not args_cli.disable_fabric) - + env_cfg = parse_env_cfg( + args_cli.task, device=args_cli.device, num_envs=args_cli.num_envs, use_fabric=not args_cli.disable_fabric + ) + agent_cfg = load_cfg_from_registry(args_cli.task, "rl_games_cfg_entry_point") # specify directory for logging experiments diff --git a/scripts/reinforcement_learning/sb3/play.py b/scripts/reinforcement_learning/sb3/play.py index 4f29f5b6fc4..f9497e6ad91 100644 --- a/scripts/reinforcement_learning/sb3/play.py +++ b/scripts/reinforcement_learning/sb3/play.py @@ -81,7 +81,9 @@ def main(): """Play with stable-baselines agent.""" # parse configuration - env_cfg = parse_env_cfg(args_cli.task, device=args_cli.device, num_envs=args_cli.num_envs, use_fabric=not args_cli.disable_fabric) + env_cfg = parse_env_cfg( + args_cli.task, device=args_cli.device, num_envs=args_cli.num_envs, use_fabric=not args_cli.disable_fabric + ) task_name = args_cli.task.split(":")[-1] train_task_name = task_name.replace("-Play", "") diff --git a/scripts/reinforcement_learning/skrl/play.py b/scripts/reinforcement_learning/skrl/play.py index 1a1f7085dc5..b1a7202eb3d 100644 --- a/scripts/reinforcement_learning/skrl/play.py +++ b/scripts/reinforcement_learning/skrl/play.py @@ -110,7 +110,9 @@ def main(): task_name = args_cli.task.split(":")[-1] # parse configuration - env_cfg = parse_env_cfg(args_cli.task, device=args_cli.device, num_envs=args_cli.num_envs, use_fabric=not args_cli.disable_fabric) + env_cfg = parse_env_cfg( + args_cli.task, device=args_cli.device, num_envs=args_cli.num_envs, use_fabric=not args_cli.disable_fabric + ) try: experiment_cfg = load_cfg_from_registry(task_name, f"skrl_{algorithm}_cfg_entry_point") except ValueError: diff --git a/scripts/sim2sim_transfer/rsl_rl_transfer.py b/scripts/sim2sim_transfer/rsl_rl_transfer.py index aeab61a768d..4d6a7ae65c2 100644 --- a/scripts/sim2sim_transfer/rsl_rl_transfer.py +++ b/scripts/sim2sim_transfer/rsl_rl_transfer.py @@ -147,7 +147,7 @@ def main(): num_envs=args_cli.num_envs, use_fabric=not args_cli.disable_fabric, ) - + agent_cfg: RslRlOnPolicyRunnerCfg = cli_args.parse_rsl_rl_cfg(task_name, args_cli) # specify directory for logging experiments diff --git a/source/isaaclab/isaaclab/envs/ui/base_env_window.py b/source/isaaclab/isaaclab/envs/ui/base_env_window.py index 1e7aa24a7cc..a122513e3ce 100644 --- a/source/isaaclab/isaaclab/envs/ui/base_env_window.py +++ b/source/isaaclab/isaaclab/envs/ui/base_env_window.py @@ -111,21 +111,21 @@ def __del__(self): def _check_live_plots_enabled(self) -> bool: """Check if any visualizer has live plots enabled. - + Returns: True if any visualizer supports and has live plots enabled, False otherwise. """ # Check if simulation has visualizers - if not hasattr(self.env.sim, '_visualizers'): + if not hasattr(self.env.sim, "_visualizers"): return False - + # Check each visualizer for visualizer in self.env.sim._visualizers: # Check if visualizer supports live plots and has it enabled - if hasattr(visualizer, 'cfg') and hasattr(visualizer.cfg, 'enable_live_plots'): + if hasattr(visualizer, "cfg") and hasattr(visualizer.cfg, "enable_live_plots"): if visualizer.supports_live_plots() and visualizer.cfg.enable_live_plots: return True - + return False """ @@ -447,11 +447,11 @@ def _create_debug_vis_ui_element(self, name: str, elem: object): is_checked = (hasattr(elem.cfg, "debug_vis") and elem.cfg.debug_vis) or ( hasattr(elem, "debug_vis") and elem.debug_vis ) - + # Auto-enable live plots for ManagerLiveVisualizer if visualizer has enable_live_plots=True if isinstance(elem, ManagerLiveVisualizer) and self._enable_live_plots: is_checked = True - + self.ui_window_elements[f"{name}_cb"] = SimpleCheckBox( model=omni.ui.SimpleBoolModel(), enabled=elem.has_debug_vis_implementation, @@ -465,7 +465,7 @@ def _create_debug_vis_ui_element(self, name: str, elem: object): self.ui_window_elements[f"{name}_panel"] = omni.ui.Frame(width=omni.ui.Fraction(1)) if not elem.set_vis_frame(self.ui_window_elements[f"{name}_panel"]): print(f"Frame failed to set for ManagerLiveVisualizer: {name}") - + # Pass the enable_live_plots flag to the visualizer elem._auto_expand_frames = self._enable_live_plots diff --git a/source/isaaclab/isaaclab/sim/_impl/newton_manager.py b/source/isaaclab/isaaclab/sim/_impl/newton_manager.py index 8ba5777314e..6d7b42ccd2f 100644 --- a/source/isaaclab/isaaclab/sim/_impl/newton_manager.py +++ b/source/isaaclab/isaaclab/sim/_impl/newton_manager.py @@ -3,7 +3,6 @@ # # SPDX-License-Identifier: BSD-3-Clause -import ctypes import numpy as np import re diff --git a/source/isaaclab/isaaclab/sim/scene_data_provider.py b/source/isaaclab/isaaclab/sim/scene_data_provider.py index ac7c46f119f..2114cd1766c 100644 --- a/source/isaaclab/isaaclab/sim/scene_data_provider.py +++ b/source/isaaclab/isaaclab/sim/scene_data_provider.py @@ -20,13 +20,13 @@ # Lazy import warp dependencies for OV visualizer support def _get_warp_kernel(): """Get the warp kernel for syncing fabric transforms. - + Returns the kernel only when warp is available, avoiding import errors when warp is not installed. """ try: import warp as wp - + # Define warp kernel for syncing transforms @wp.kernel(enable_backward=False) def set_vec3d_array( @@ -38,7 +38,7 @@ def set_vec3d_array( idx = int(indices[i]) new_val = newton_vals[idx] fabric_vals[i] = wp.transpose(wp.mat44d(wp.math.transform_to_matrix(new_val))) - + return set_vec3d_array except ImportError: return None @@ -46,12 +46,12 @@ def set_vec3d_array( class SceneDataProvider: """Unified scene data provider for all physics and rendering backends. - + This class provides: - Access to physics state and model for visualizers (Newton OpenGL, Rerun) - Synchronization of physics state to USD Fabric for OV visualizer - Conditional updates based on active visualizers to avoid unnecessary work - + The provider handles both Newton-specific data (state, model) and OV-specific synchronization (fabric transforms) within a single class to keep the abstraction simple while supporting multiple backends. @@ -59,7 +59,7 @@ class SceneDataProvider: def __init__(self, visualizer_cfgs: list[Any] | None = None): """Initialize the scene data provider with visualizer configurations. - + Args: visualizer_cfgs: List of visualizer configurations to determine which backends are active. """ @@ -67,82 +67,84 @@ def __init__(self, visualizer_cfgs: list[Any] | None = None): self._has_rerun_visualizer = False self._has_ov_visualizer = False self._is_initialized = False - + # Determine which visualizers are enabled from configs if visualizer_cfgs: for cfg in visualizer_cfgs: - viz_type = getattr(cfg, 'visualizer_type', None) - if viz_type == 'newton': + viz_type = getattr(cfg, "visualizer_type", None) + if viz_type == "newton": self._has_newton_visualizer = True - elif viz_type == 'rerun': + elif viz_type == "rerun": self._has_rerun_visualizer = True - elif viz_type == 'omniverse': + elif viz_type == "omniverse": self._has_ov_visualizer = True - + self._is_initialized = True - + def update(self) -> None: """Update scene data for visualizers. - + This method: - Syncs Newton transforms to USD Fabric (if OV visualizer is active) - Can be extended for other backend-specific updates - + Note: Only performs work if necessary visualizers are active to avoid overhead. """ if not self._is_initialized: return - + # Sync fabric transforms only if OV visualizer is active if self._has_ov_visualizer: self._sync_fabric_transforms() - + def get_state(self) -> State | None: """Get physics state for Newton-based visualizers. - + Returns: Newton State object, or None if not available. """ # State is needed by Newton OpenGL and Rerun visualizers if not (self._has_newton_visualizer or self._has_rerun_visualizer): return None - + # Lazy import to avoid loading Newton if not needed try: from isaaclab.sim._impl.newton_manager import NewtonManager + return NewtonManager._state_0 except ImportError: return None - + def get_model(self) -> Model | None: """Get physics model for Newton-based visualizers. - + Returns: Newton Model object, or None if not available. """ # Model is needed by Newton OpenGL and Rerun visualizers if not (self._has_newton_visualizer or self._has_rerun_visualizer): return None - + # Lazy import to avoid loading Newton if not needed try: from isaaclab.sim._impl.newton_manager import NewtonManager + return NewtonManager._model except ImportError: return None - + def _sync_fabric_transforms(self) -> None: """Sync Newton transforms to USD Fabric for OV visualizer. - + This method updates the USD Fabric with the latest physics transforms from Newton. It uses a warp kernel to efficiently copy transform data on the GPU. - + The sync process: 1. Selects USD prims that have both worldMatrix and newton index attributes 2. Creates fabric arrays for transforms and indices 3. Launches warp kernel to copy Newton body transforms to USD Fabric - + Note: This is only called when OV visualizer is active to avoid unnecessary GPU work. """ @@ -150,12 +152,13 @@ def _sync_fabric_transforms(self) -> None: set_vec3d_array = _get_warp_kernel() if set_vec3d_array is None: return - + try: import usdrt import warp as wp + from isaaclab.sim._impl.newton_manager import NewtonManager - + # Select all prims with required attributes selection = NewtonManager._usdrt_stage.SelectPrims( require_attrs=[ @@ -164,11 +167,11 @@ def _sync_fabric_transforms(self) -> None: ], device="cuda:0", ) - + # Create fabric arrays for indices and transforms fabric_newton_indices = wp.fabricarray(selection, NewtonManager._newton_index_attr) current_transforms = wp.fabricarray(selection, "omni:fabric:worldMatrix") - + # Launch warp kernel to sync transforms wp.launch( set_vec3d_array, diff --git a/source/isaaclab/isaaclab/sim/simulation_cfg.py b/source/isaaclab/isaaclab/sim/simulation_cfg.py index 06139132f01..fb5bf6b1bba 100644 --- a/source/isaaclab/isaaclab/sim/simulation_cfg.py +++ b/source/isaaclab/isaaclab/sim/simulation_cfg.py @@ -12,10 +12,10 @@ from typing import Literal from isaaclab.utils import configclass +from isaaclab.visualizers import NewtonVisualizerCfg, OVVisualizerCfg, RerunVisualizerCfg, VisualizerCfg from ._impl.newton_manager_cfg import NewtonCfg from .spawners.materials import RigidBodyMaterialCfg -from isaaclab.visualizers import VisualizerCfg, NewtonVisualizerCfg, OVVisualizerCfg, RerunVisualizerCfg @configclass @@ -198,38 +198,42 @@ class SimulationCfg: """Render settings. Default is RenderCfg().""" # visualizer_cfgs: list[VisualizerCfg] | VisualizerCfg | None = NewtonVisualizerCfg() - visualizer_cfgs: list[VisualizerCfg] | VisualizerCfg | None = [OVVisualizerCfg(), NewtonVisualizerCfg()] + visualizer_cfgs: list[VisualizerCfg] | VisualizerCfg | None = [ + OVVisualizerCfg(), + NewtonVisualizerCfg(), + RerunVisualizerCfg(), + ] """Visualizer settings. Default is NewtonVisualizerCfg(). - + This field supports multiple visualizer backends for debug visualization and monitoring during simulation. It accepts: - A single VisualizerCfg: One visualizer will be created - A list of VisualizerCfg: Multiple visualizers will be created - None or empty list: No visualizers will be created - + Supported visualizer backends: - NewtonVisualizerCfg: Lightweight OpenGL-based visualizer (default) - - OVVisualizerCfg: Omniverse-based high-fidelity visualizer + - OVVisualizerCfg: Omniverse-based high-fidelity visualizer - RerunVisualizerCfg: Web-based Rerun visualizer - + Examples: # Disable all visualizers cfg.sim.visualizer_cfgs = [] - + # Use default visualizer (NewtonVisualizerCfg) cfg = SimulationCfg() - + # Single custom visualizer from isaaclab.visualizers import OVVisualizerCfg cfg = SimulationCfg(visualizer_cfgs=OVVisualizerCfg()) - + # Multiple visualizers with custom configuration from isaaclab.visualizers import NewtonVisualizerCfg, RerunVisualizerCfg cfg = SimulationCfg(visualizer_cfgs=[ NewtonVisualizerCfg(camera_position=(10.0, 0.0, 3.0)), RerunVisualizerCfg(server_address="127.0.0.1:9876") ]) - + Note: Visualizers are separate from rendering backends (for cameras/sensors). They are intended for debug visualization and monitoring only. diff --git a/source/isaaclab/isaaclab/sim/simulation_context.py b/source/isaaclab/isaaclab/sim/simulation_context.py index 2fa7259aa03..4d959919cab 100644 --- a/source/isaaclab/isaaclab/sim/simulation_context.py +++ b/source/isaaclab/isaaclab/sim/simulation_context.py @@ -31,12 +31,12 @@ from isaaclab.sim._impl.newton_manager import NewtonManager from isaaclab.sim.utils import create_new_stage_in_memory, use_stage +from isaaclab.visualizers import Visualizer -from .simulation_cfg import SimulationCfg from .scene_data_provider import SceneDataProvider +from .simulation_cfg import SimulationCfg from .spawners import DomeLightCfg, GroundPlaneCfg from .utils import bind_physics_material -from isaaclab.visualizers import Visualizer class SimulationContext(_SimulationContext): @@ -548,20 +548,20 @@ def forward(self) -> None: def initialize_visualizers(self) -> None: """Initialize all configured visualizers. - + This method creates and initializes visualizers based on the configuration provided in SimulationCfg.visualizer_cfgs. It supports: - A single VisualizerCfg: Creates one visualizer - A list of VisualizerCfg: Creates multiple visualizers - None or empty list: No visualizers are created - + Note: Visualizers are automatically skipped when running in headless mode. """ # Skip visualizers in headless mode if not self._has_gui and not self._offscreen_render: return - + # Handle different input formats visualizer_cfgs = [] if self.cfg.visualizer_cfgs is not None: @@ -582,36 +582,32 @@ def initialize_visualizers(self) -> None: # Build scene data dict with only what this visualizer needs scene_data = {} - + # Newton and Rerun visualizers only need scene_data_provider if viz_cfg.visualizer_type in ("newton", "rerun"): scene_data["scene_data_provider"] = self._scene_data_provider - + # OV visualizer needs USD stage and simulation context elif viz_cfg.visualizer_type == "omniverse": scene_data["usd_stage"] = self.stage scene_data["simulation_context"] = self - + # Initialize visualizer with minimal required data visualizer.initialize(scene_data) self._visualizers.append(visualizer) - omni.log.info( - f"Initialized visualizer: {type(visualizer).__name__} " - f"(type: {viz_cfg.visualizer_type})" - ) + omni.log.info(f"Initialized visualizer: {type(visualizer).__name__} (type: {viz_cfg.visualizer_type})") except Exception as e: omni.log.error( - f"Failed to initialize visualizer '{viz_cfg.visualizer_type}' " - f"({type(viz_cfg).__name__}): {e}" + f"Failed to initialize visualizer '{viz_cfg.visualizer_type}' ({type(viz_cfg).__name__}): {e}" ) def step_visualizers(self, dt: float) -> None: """Update all active visualizers. - + This method steps all initialized visualizers and updates their state. It also handles visualizer pause states and removes closed visualizers. - + Args: dt: Time step in seconds. """ @@ -635,11 +631,8 @@ def step_visualizers(self, dt: float) -> None: # Visualizers fetch backend-specific state themselves visualizer.step(0.0, state=None) - # Skip rendering if visualizer has rendering paused - if visualizer.is_rendering_paused(): - continue - - # Normal step: visualizers fetch backend-specific state themselves + # Always call step to process events, even if rendering is paused + # The visualizer's step() method handles pause state internally visualizer.step(dt, state=None) except Exception as e: @@ -662,7 +655,7 @@ def close_visualizers(self) -> None: visualizer.close() except Exception as e: omni.log.error(f"Error closing visualizer '{type(visualizer).__name__}': {e}") - + self._visualizers.clear() omni.log.info("All visualizers closed") @@ -705,11 +698,11 @@ def reset(self, soft: bool = False): if not soft: for _ in range(2): self.render() - + # Initialize visualizers after simulation is set up (only on first reset) if not soft and not self._visualizers: self.initialize_visualizers() - + self._disable_app_control_on_stop_handle = False def step(self, render: bool = True): @@ -861,7 +854,7 @@ def clear_instance(cls): cls._instance._app_control_on_stop_handle.unsubscribe() cls._instance._app_control_on_stop_handle = None # close all visualizers - if hasattr(cls._instance, '_visualizers'): + if hasattr(cls._instance, "_visualizers"): cls._instance.close_visualizers() # call parent to clear the instance super().clear_instance() @@ -1040,23 +1033,23 @@ def build_simulation_context( def enable_visualizers(env_cfg, train_mode: bool = True) -> None: """Enable visualizers for an environment configuration. - + Sets visualizers to Newton OpenGL if none configured, and sets train_mode. - + Args: env_cfg: Environment configuration (DirectRLEnvCfg or ManagerBasedRLEnvCfg) to modify. train_mode: Whether to run visualizers in training mode (True) or play/inference mode (False). - + Example: >>> import isaaclab.sim as sim_utils >>> if args_cli.visualize: ... sim_utils.enable_visualizers(env_cfg) """ from isaaclab.visualizers import NewtonVisualizerCfg - + if env_cfg.sim.visualizer_cfgs is None: env_cfg.sim.visualizer_cfgs = NewtonVisualizerCfg() - + # Set train_mode on all configured visualizers if isinstance(env_cfg.sim.visualizer_cfgs, list): for viz_cfg in env_cfg.sim.visualizer_cfgs: diff --git a/source/isaaclab/isaaclab/visualizers/__init__.py b/source/isaaclab/isaaclab/visualizers/__init__.py index 3a2dd027d56..58f02399a78 100644 --- a/source/isaaclab/isaaclab/visualizers/__init__.py +++ b/source/isaaclab/isaaclab/visualizers/__init__.py @@ -25,17 +25,18 @@ from typing import TYPE_CHECKING, Any -# Import base classes first -from .visualizer import Visualizer -from .visualizer_cfg import VisualizerCfg - # Import config classes (no circular dependency) from .newton_visualizer_cfg import NewtonVisualizerCfg from .ov_visualizer_cfg import OVVisualizerCfg from .rerun_visualizer_cfg import RerunVisualizerCfg +# Import base classes first +from .visualizer import Visualizer +from .visualizer_cfg import VisualizerCfg + if TYPE_CHECKING: from typing import Type + from .newton_visualizer import NewtonVisualizer from .ov_visualizer import OVVisualizer from .rerun_visualizer import RerunVisualizer @@ -52,19 +53,20 @@ "get_visualizer_class", ] + # Register only selected visualizers to reduce unnecessary imports -def get_visualizer_class(name: str) -> Type[Visualizer] | None: +def get_visualizer_class(name: str) -> type[Visualizer] | None: """Get a visualizer class by name (lazy-loaded). - + Visualizer classes are imported only when requested to avoid loading unnecessary dependencies. - + Args: name: Visualizer type name (e.g., 'newton', 'rerun', 'omniverse', 'ov'). - + Returns: Visualizer class if found, None otherwise. - + Example: >>> visualizer_cls = get_visualizer_class('newton') >>> if visualizer_cls: @@ -73,20 +75,23 @@ def get_visualizer_class(name: str) -> Type[Visualizer] | None: # Check if already loaded if name in _VISUALIZER_REGISTRY: return _VISUALIZER_REGISTRY[name] - + # Lazy-load visualizer on first access try: if name == "newton": from .newton_visualizer import NewtonVisualizer + _VISUALIZER_REGISTRY["newton"] = NewtonVisualizer return NewtonVisualizer elif name in ("omniverse", "ov"): from .ov_visualizer import OVVisualizer + _VISUALIZER_REGISTRY["omniverse"] = OVVisualizer _VISUALIZER_REGISTRY["ov"] = OVVisualizer # Alias return OVVisualizer elif name == "rerun": from .rerun_visualizer import RerunVisualizer + _VISUALIZER_REGISTRY["rerun"] = RerunVisualizer return RerunVisualizer else: @@ -94,6 +99,6 @@ def get_visualizer_class(name: str) -> Type[Visualizer] | None: except ImportError as e: # Log import error but don't crash - visualizer just won't be available import warnings + warnings.warn(f"Failed to load visualizer '{name}': {e}", ImportWarning) return None - diff --git a/source/isaaclab/isaaclab/visualizers/newton_visualizer.py b/source/isaaclab/isaaclab/visualizers/newton_visualizer.py index bee4779975d..84276d61cf0 100644 --- a/source/isaaclab/isaaclab/visualizers/newton_visualizer.py +++ b/source/isaaclab/isaaclab/visualizers/newton_visualizer.py @@ -7,9 +7,9 @@ from __future__ import annotations -from typing import TYPE_CHECKING, Any +import contextlib +from typing import Any -import omni.log import warp as wp from newton.viewer import ViewerGL @@ -19,7 +19,7 @@ class NewtonViewerGL(ViewerGL): """Wrapper around Newton's ViewerGL with training/rendering pause controls. - + Adds two pause modes: - Training pause: Stops physics simulation, continues rendering - Rendering pause: Stops rendering updates, continues physics (SPACE key) @@ -43,15 +43,11 @@ def is_training_paused(self) -> bool: def is_rendering_paused(self) -> bool: return self._paused_rendering - - def is_paused(self) -> bool: - # duplicate to above for now - return self._paused_rendering def _render_training_controls(self, imgui): imgui.separator() imgui.text("IsaacLab Controls") - + # Pause training/simulation button pause_label = "Resume Training" if self._paused_training else "Pause Training" if imgui.button(pause_label): @@ -61,7 +57,7 @@ def _render_training_controls(self, imgui): rendering_label = "Resume Rendering" if self._paused_rendering else "Pause Rendering" if imgui.button(rendering_label): self._paused_rendering = not self._paused_rendering - self._paused = self._paused_rendering + self._paused = self._paused_rendering # Sync with parent class pause state # Visualizer update frequency control imgui.text("Visualizer Update Frequency") @@ -89,7 +85,7 @@ def on_key_press(self, symbol, modifiers): if symbol == pyglet.window.key.SPACE: self._paused_rendering = not self._paused_rendering - self._paused = self._paused_rendering + self._paused = self._paused_rendering # Sync with parent class pause state return super().on_key_press(symbol, modifiers) @@ -233,7 +229,7 @@ def _render_left_panel(self): class NewtonVisualizer(Visualizer): """Newton OpenGL visualizer for Isaac Lab. - + Lightweight OpenGL-based visualization with training/rendering pause controls. """ @@ -255,11 +251,11 @@ def initialize(self, scene_data: dict[str, Any] | None = None) -> None: # Import NewtonManager for metadata access from isaaclab.sim._impl.newton_manager import NewtonManager - + # Store scene data provider for accessing physics state if scene_data and "scene_data_provider" in scene_data: self._scene_data_provider = scene_data["scene_data_provider"] - + # Get Newton-specific data from scene data provider if self._scene_data_provider: self._model = self._scene_data_provider.get_model() @@ -268,13 +264,10 @@ def initialize(self, scene_data: dict[str, Any] | None = None) -> None: # Fallback: direct access to NewtonManager (for backward compatibility) self._model = NewtonManager._model self._state = NewtonManager._state_0 - + if self._model is None: - raise RuntimeError( - "Newton visualizer requires Newton Model. " - "Ensure Newton physics is initialized first." - ) - + raise RuntimeError("Newton visualizer requires Newton Model. Ensure Newton physics is initialized first.") + # Build metadata from NewtonManager metadata = { "physics_backend": "newton", @@ -316,8 +309,6 @@ def initialize(self, scene_data: dict[str, Any] | None = None) -> None: self._viewer.renderer.sky_lower = self.cfg.ground_color self._viewer.renderer._light_color = self.cfg.light_color - # TODO: Partial visualization will be implemented through a new cloner feature - self._is_initialized = True def step(self, dt: float, state: Any | None = None) -> None: @@ -327,13 +318,14 @@ def step(self, dt: float, state: Any | None = None) -> None: self._sim_time += dt self._step_counter += 1 - + # Fetch updated state from scene data provider if self._scene_data_provider: self._state = self._scene_data_provider.get_state() else: # Fallback: direct access to NewtonManager from isaaclab.sim._impl.newton_manager import NewtonManager + self._state = NewtonManager._state_0 # Only update visualizer at the specified frequency @@ -341,7 +333,7 @@ def step(self, dt: float, state: Any | None = None) -> None: if self._step_counter % update_frequency != 0: return - try: + with contextlib.suppress(Exception): if not self._viewer.is_paused(): self._viewer.begin_frame(self._sim_time) if self._state is not None: @@ -349,8 +341,6 @@ def step(self, dt: float, state: Any | None = None) -> None: self._viewer.end_frame() else: self._viewer._update() - except Exception: - pass def close(self) -> None: """Close visualizer and clean up resources.""" @@ -365,14 +355,14 @@ def is_running(self) -> bool: if not self._is_initialized or self._is_closed or self._viewer is None: return False return self._viewer.is_running() - + def supports_markers(self) -> bool: - """Newton visualizer does not support USD-based markers.""" + """Newton visualizer does not have this feature yet.""" return False - + def supports_live_plots(self) -> bool: - """Newton visualizer supports ImGui-based plots.""" - return True + """Newton visualizer does not have this feature yet.""" + return False def is_training_paused(self) -> bool: """Check if training is paused.""" @@ -385,5 +375,3 @@ def is_rendering_paused(self) -> bool: if not self._is_initialized or self._viewer is None: return False return self._viewer.is_rendering_paused() - - diff --git a/source/isaaclab/isaaclab/visualizers/newton_visualizer_cfg.py b/source/isaaclab/isaaclab/visualizers/newton_visualizer_cfg.py index 98544d5f549..a6533f4ba19 100644 --- a/source/isaaclab/isaaclab/visualizers/newton_visualizer_cfg.py +++ b/source/isaaclab/isaaclab/visualizers/newton_visualizer_cfg.py @@ -15,10 +15,10 @@ @configclass class NewtonVisualizerCfg(VisualizerCfg): """Configuration for Newton OpenGL visualizer. - + Lightweight OpenGL-based visualizer with real-time 3D rendering, interactive camera controls, and debug visualization (contacts, joints, springs, COM). - + Requires: pyglet >= 2.1.6, imgui_bundle >= 1.92.0 """ diff --git a/source/isaaclab/isaaclab/visualizers/ov_visualizer.py b/source/isaaclab/isaaclab/visualizers/ov_visualizer.py index 451120c6b34..e2c5da0cc4e 100644 --- a/source/isaaclab/isaaclab/visualizers/ov_visualizer.py +++ b/source/isaaclab/isaaclab/visualizers/ov_visualizer.py @@ -1,3 +1,8 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + # Copyright (c) 2022-2025, The Isaac Lab Project Developers. # All rights reserved. # @@ -8,135 +13,128 @@ from __future__ import annotations import asyncio -import omni.log from typing import Any +import omni.log +from pxr import UsdGeom + from .ov_visualizer_cfg import OVVisualizerCfg from .visualizer import Visualizer class OVVisualizer(Visualizer): """Omniverse visualizer using Isaac Sim viewport. - + Renders USD stage with VisualizationMarkers and LivePlots. Can attach to existing app or launch standalone. """ - + def __init__(self, cfg: OVVisualizerCfg): super().__init__(cfg) self.cfg: OVVisualizerCfg = cfg - + self._simulation_app = None self._viewport_window = None self._viewport_api = None self._is_initialized = False self._sim_time = 0.0 self._step_counter = 0 - + def initialize(self, scene_data: dict[str, Any] | None = None) -> None: """Initialize OV visualizer.""" if self._is_initialized: omni.log.warn("[OVVisualizer] Already initialized.") return - + usd_stage = None simulation_context = None if scene_data is not None: usd_stage = scene_data.get("usd_stage") simulation_context = scene_data.get("simulation_context") - + if usd_stage is None: raise RuntimeError("OV visualizer requires a USD stage.") - + # Build metadata from simulation context if available metadata = {} if simulation_context is not None: # Try to get num_envs from the simulation context's scene if available num_envs = 0 - if hasattr(simulation_context, 'scene') and simulation_context.scene is not None: - if hasattr(simulation_context.scene, 'num_envs'): + if hasattr(simulation_context, "scene") and simulation_context.scene is not None: + if hasattr(simulation_context.scene, "num_envs"): num_envs = simulation_context.scene.num_envs - + # Detect physics backend (could be extended to check actual backend type) physics_backend = "newton" # Default for now, could be made more sophisticated - + metadata = { "num_envs": num_envs, "physics_backend": physics_backend, "env_prim_pattern": "/World/envs/env_{}", # Standard pattern } - + self._ensure_simulation_app() self._setup_viewport(usd_stage, metadata) - - # TODO: Partial visualization will be implemented through a new cloner feature - + num_envs = metadata.get("num_envs", 0) physics_backend = metadata.get("physics_backend", "unknown") omni.log.info(f"[OVVisualizer] Initialized ({num_envs} envs, {physics_backend} physics)") - + self._is_initialized = True - + def step(self, dt: float, state: Any | None = None) -> None: """Update visualizer (no-op for OV - USD stage is auto-synced by Newton).""" if not self._is_initialized: return self._sim_time += dt self._step_counter += 1 - + def close(self) -> None: """Clean up visualizer resources.""" if not self._is_initialized: return - + # Note: We don't close the SimulationApp here as it's managed by AppLauncher self._simulation_app = None self._viewport_window = None self._viewport_api = None self._is_initialized = False - + def is_running(self) -> bool: """Check if visualizer is running.""" if self._simulation_app is None: return False return self._simulation_app.is_running() - + def is_training_paused(self) -> bool: """Check if training is paused (always False for OV).""" return False - + def supports_markers(self) -> bool: # Should we add marker configuration, or let the env itself handle it. """Supports markers via USD prims.""" return True - + def supports_live_plots(self) -> bool: """Supports live plots via Isaac Lab UI. - + When enable_live_plots=True in OVVisualizerCfg: - Automatically enables all manager visualizers (checkboxes checked) - Keeps plot frames expanded by default - Plots appear in the IsaacLab window docked to the right of the viewport """ return True - + # ------------------------------------------------------------------ # Private methods # ------------------------------------------------------------------ - + def _ensure_simulation_app(self) -> None: - """Ensure Isaac Sim app is running. - - The OV visualizer requires Isaac Sim to be launched via AppLauncher before initialization. - In typical usage (e.g., training scripts), AppLauncher handles this automatically. - - Note: Future enhancement could add standalone app launching for non-training workflows, - but this is not currently needed as AppLauncher is always used in practice. - """ + """Ensure Isaac Sim app is running.""" try: # Check if omni.kit.app is available (indicates Isaac Sim is running) import omni.kit.app - + # Get the running app instance app = omni.kit.app.get_app() if app is None or not app.is_running(): @@ -145,21 +143,21 @@ def _ensure_simulation_app(self) -> None: "OV visualizer requires Isaac Sim to be launched via AppLauncher before initialization. " "Ensure your script calls AppLauncher before creating the environment." ) - + # Try to get SimulationApp instance for headless check try: from isaacsim import SimulationApp - + # Check various ways SimulationApp might store its instance sim_app = None - if hasattr(SimulationApp, '_instance') and SimulationApp._instance is not None: + if hasattr(SimulationApp, "_instance") and SimulationApp._instance is not None: sim_app = SimulationApp._instance - elif hasattr(SimulationApp, 'instance') and callable(SimulationApp.instance): + elif hasattr(SimulationApp, "instance") and callable(SimulationApp.instance): sim_app = SimulationApp.instance() - + if sim_app is not None: self._simulation_app = sim_app - + # Check if running in headless mode if self._simulation_app.config.get("headless", False): omni.log.warn( @@ -172,23 +170,22 @@ def _ensure_simulation_app(self) -> None: # App is running but we couldn't get SimulationApp instance # This is okay - we can still use omni APIs omni.log.info("[OVVisualizer] Isaac Sim app is running (via omni.kit.app).") - + except ImportError: # SimulationApp not available, but omni.kit.app is running omni.log.info("[OVVisualizer] Using running Isaac Sim app (SimulationApp module not available).") - + except ImportError as e: raise ImportError( - f"[OVVisualizer] Could not import omni.kit.app: {e}. " - "Isaac Sim may not be installed or not running." + f"[OVVisualizer] Could not import omni.kit.app: {e}. Isaac Sim may not be installed or not running." ) - + def _setup_viewport(self, usd_stage, metadata: dict) -> None: """Setup viewport with camera and window size.""" try: import omni.kit.viewport.utility as vp_utils from omni.ui import DockPosition - + # Create new viewport or use existing if self.cfg.create_viewport and self.cfg.viewport_name: # Map dock position string to enum @@ -199,7 +196,7 @@ def _setup_viewport(self, usd_stage, metadata: dict) -> None: "SAME": DockPosition.SAME, } dock_pos = dock_position_map.get(self.cfg.dock_position.upper(), DockPosition.SAME) - + # Create new viewport with proper API self._viewport_window = vp_utils.create_viewport_window( name=self.cfg.viewport_name, @@ -209,12 +206,12 @@ def _setup_viewport(self, usd_stage, metadata: dict) -> None: position_y=50, docked=True, ) - + omni.log.info(f"[OVVisualizer] Created viewport '{self.cfg.viewport_name}'") - + # Dock the viewport asynchronously (needs to wait for window creation) asyncio.ensure_future(self._dock_viewport_async(self.cfg.viewport_name, dock_pos)) - + # Create dedicated camera for this viewport if self._viewport_window: self._create_and_assign_camera(usd_stage) @@ -222,11 +219,11 @@ def _setup_viewport(self, usd_stage, metadata: dict) -> None: # Use existing viewport by name, or fall back to active viewport if self.cfg.viewport_name: self._viewport_window = vp_utils.get_viewport_window_by_name(self.cfg.viewport_name) - + if self._viewport_window is None: omni.log.warn( f"[OVVisualizer] Viewport '{self.cfg.viewport_name}' not found. " - f"Using active viewport instead." + "Using active viewport instead." ) self._viewport_window = vp_utils.get_active_viewport_window() else: @@ -234,35 +231,37 @@ def _setup_viewport(self, usd_stage, metadata: dict) -> None: else: self._viewport_window = vp_utils.get_active_viewport_window() omni.log.info("[OVVisualizer] Using existing active viewport") - + if self._viewport_window is None: omni.log.warn("[OVVisualizer] Could not get/create viewport.") return - + # Get viewport API for camera control self._viewport_api = self._viewport_window.viewport_api - + # Set camera pose (uses existing camera if not created above) self._set_viewport_camera(self.cfg.camera_position, self.cfg.camera_target) - - omni.log.info(f"[OVVisualizer] Viewport configured (size: {self.cfg.window_width}x{self.cfg.window_height})") - + + omni.log.info( + f"[OVVisualizer] Viewport configured (size: {self.cfg.window_width}x{self.cfg.window_height})" + ) + except ImportError as e: omni.log.warn(f"[OVVisualizer] Viewport utilities unavailable: {e}") except Exception as e: omni.log.error(f"[OVVisualizer] Error setting up viewport: {e}") - + async def _dock_viewport_async(self, viewport_name: str, dock_position) -> None: """Dock viewport window asynchronously after it's created. - + Args: viewport_name: Name of the viewport window to dock. dock_position: DockPosition enum value for where to dock. """ try: - import omni.ui import omni.kit.app - + import omni.ui + # Wait for the viewport window to be created in the workspace viewport_window = None for i in range(10): # Try up to 10 frames @@ -271,11 +270,13 @@ async def _dock_viewport_async(self, viewport_name: str, dock_position) -> None: omni.log.info(f"[OVVisualizer] Found viewport window '{viewport_name}' after {i} frames") break await omni.kit.app.get_app().next_update_async() - + if not viewport_window: - omni.log.warn(f"[OVVisualizer] Could not find viewport window '{viewport_name}' in workspace for docking.") + omni.log.warn( + f"[OVVisualizer] Could not find viewport window '{viewport_name}' in workspace for docking." + ) return - + # Get the main viewport to dock relative to main_viewport = omni.ui.Workspace.get_window("Viewport") if not main_viewport: @@ -284,83 +285,79 @@ async def _dock_viewport_async(self, viewport_name: str, dock_position) -> None: main_viewport = omni.ui.Workspace.get_window(alt_name) if main_viewport: break - + if main_viewport and main_viewport != viewport_window: # Dock the new viewport relative to the main viewport viewport_window.dock_in(main_viewport, dock_position, 0.5) - + # Wait a frame for docking to complete await omni.kit.app.get_app().next_update_async() - + # Make the new viewport the active/focused tab # Try multiple methods to ensure it becomes active viewport_window.focus() viewport_window.visible = True - + # Wait another frame and focus again (sometimes needed for tabs) await omni.kit.app.get_app().next_update_async() viewport_window.focus() - - omni.log.info(f"[OVVisualizer] Docked viewport '{viewport_name}' at position {self.cfg.dock_position} and set as active") + + omni.log.info( + f"[OVVisualizer] Docked viewport '{viewport_name}' at position {self.cfg.dock_position} and set as" + " active" + ) else: - omni.log.info(f"[OVVisualizer] Could not find main viewport for docking. Viewport '{viewport_name}' will remain floating.") - + omni.log.info( + f"[OVVisualizer] Could not find main viewport for docking. Viewport '{viewport_name}' will remain" + " floating." + ) + except Exception as e: omni.log.warn(f"[OVVisualizer] Error docking viewport: {e}") - + def _create_and_assign_camera(self, usd_stage) -> None: """Create a dedicated camera for this viewport and assign it.""" try: - from pxr import UsdGeom, Gf - # Create camera prim path based on viewport name camera_path = f"/World/Cameras/{self.cfg.viewport_name}_Camera" - + # Check if camera already exists camera_prim = usd_stage.GetPrimAtPath(camera_path) if not camera_prim.IsValid(): # Create camera prim - camera = UsdGeom.Camera.Define(usd_stage, camera_path) + UsdGeom.Camera.Define(usd_stage, camera_path) omni.log.info(f"[OVVisualizer] Created camera: {camera_path}") else: omni.log.info(f"[OVVisualizer] Using existing camera: {camera_path}") - + # Assign camera to viewport if self._viewport_api: self._viewport_api.set_active_camera(camera_path) omni.log.info(f"[OVVisualizer] Assigned camera '{camera_path}' to viewport '{self.cfg.viewport_name}'") - + except Exception as e: omni.log.warn(f"[OVVisualizer] Could not create/assign camera: {e}. Using default camera.") - - def _set_viewport_camera( - self, - position: tuple[float, float, float], - target: tuple[float, float, float] - ) -> None: + + def _set_viewport_camera(self, position: tuple[float, float, float], target: tuple[float, float, float]) -> None: """Set viewport camera position and target using Isaac Sim utilities.""" if self._viewport_api is None: return - + try: # Import Isaac Sim viewport utilities import isaacsim.core.utils.viewports as vp_utils - + # Get the camera prim path for this viewport camera_path = self._viewport_api.get_active_camera() if not camera_path: camera_path = "/OmniverseKit_Persp" # Default camera - + # Use Isaac Sim utility to set camera view vp_utils.set_camera_view( - eye=list(position), - target=list(target), - camera_prim_path=camera_path, - viewport_api=self._viewport_api + eye=list(position), target=list(target), camera_prim_path=camera_path, viewport_api=self._viewport_api ) - + omni.log.info(f"[OVVisualizer] Camera set: pos={position}, target={target}, camera={camera_path}") - + except Exception as e: omni.log.warn(f"[OVVisualizer] Could not set camera: {e}") - diff --git a/source/isaaclab/isaaclab/visualizers/ov_visualizer_cfg.py b/source/isaaclab/isaaclab/visualizers/ov_visualizer_cfg.py index fe8f084fb1d..c04ca0f31cf 100644 --- a/source/isaaclab/isaaclab/visualizers/ov_visualizer_cfg.py +++ b/source/isaaclab/isaaclab/visualizers/ov_visualizer_cfg.py @@ -1,3 +1,8 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + # Copyright (c) 2022-2025, The Isaac Lab Project Developers. # All rights reserved. # @@ -13,31 +18,31 @@ @configclass class OVVisualizerCfg(VisualizerCfg): """Configuration for Omniverse visualizer using Isaac Sim viewport. - + Displays USD stage, VisualizationMarkers, and LivePlots. Can attach to existing app or launch standalone. """ - + visualizer_type: str = "omniverse" """Type identifier for Omniverse visualizer.""" - + viewport_name: str | None = "Visualizer Viewport" """Viewport name to use. If None, uses active viewport.""" - + create_viewport: bool = True """Create new viewport with specified name and camera pose.""" - + dock_position: str = "SAME" """Dock position for new viewport. Options: 'LEFT', 'RIGHT', 'BOTTOM', 'SAME' (tabs with existing).""" - - window_width: int = 1280 + + window_width: int = 1280 """Viewport width in pixels.""" - + window_height: int = 720 """Viewport height in pixels.""" - + camera_position: tuple[float, float, float] = (10.0, 10.0, 3.0) """Initial camera position (x, y, z).""" - + camera_target: tuple[float, float, float] = (0.0, 0.0, 0.0) """Initial camera target/look-at point (x, y, z).""" diff --git a/source/isaaclab/isaaclab/visualizers/rerun_visualizer.py b/source/isaaclab/isaaclab/visualizers/rerun_visualizer.py index 6190d3ef7f1..9c87d27be77 100644 --- a/source/isaaclab/isaaclab/visualizers/rerun_visualizer.py +++ b/source/isaaclab/isaaclab/visualizers/rerun_visualizer.py @@ -1,3 +1,8 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + # Copyright (c) 2022-2025, The Isaac Lab Project Developers. # All rights reserved. # @@ -7,11 +12,10 @@ from __future__ import annotations -import numpy as np -import omni.log -import torch from typing import Any +import omni.log + from .rerun_visualizer_cfg import RerunVisualizerCfg from .visualizer import Visualizer @@ -20,7 +24,7 @@ import rerun as rr import rerun.blueprint as rrb from newton.viewer import ViewerRerun - + _RERUN_AVAILABLE = True except ImportError: rr = None @@ -30,9 +34,7 @@ class NewtonViewerRerun(ViewerRerun if _RERUN_AVAILABLE else object): - """Isaac Lab wrapper for Newton's ViewerRerun. - - Adds VisualizationMarkers, LivePlots, metadata display, and partial visualization.""" + """Isaac Lab wrapper for Newton's ViewerRerun.""" def __init__( self, @@ -44,8 +46,6 @@ def __init__( keep_scalar_history: bool = True, record_to_rrd: str | None = None, metadata: dict | None = None, - enable_markers: bool = True, - enable_live_plots: bool = True, ): """Initialize Newton ViewerRerun wrapper.""" # Call parent with only Newton parameters @@ -54,223 +54,73 @@ def __init__( address=address, launch_viewer=launch_viewer, app_id=app_id, + # Note: The current Newton version with IsaacLab does not support these recording flags. + # Support is available in the top of tree Newton version when we eventually upgrade. # keep_historical_data=keep_historical_data, # keep_scalar_history=keep_scalar_history, # record_to_rrd=record_to_rrd, ) - + # Isaac Lab state self._metadata = metadata or {} - self._enable_markers = enable_markers - self._enable_live_plots = enable_live_plots - - # Storage for registered markers and plots - self._registered_markers = [] - self._registered_plots = {} - + # Log metadata on initialization self._log_metadata() - + def _log_metadata(self) -> None: """Log scene metadata to Rerun as text.""" metadata_text = "# Isaac Lab Scene Metadata\n\n" - + # Physics info physics_backend = self._metadata.get("physics_backend", "unknown") metadata_text += f"**Physics Backend:** {physics_backend}\n" - + # Environment info num_envs = self._metadata.get("num_envs", 0) metadata_text += f"**Total Environments:** {num_envs}\n" - - # Physics backend info - physics_backend = self._metadata.get("physics_backend", "unknown") - metadata_text += f"**Physics:** {physics_backend}\n" - - # Visualization features - metadata_text += f"**Markers Enabled:** {self._enable_markers}\n" - metadata_text += f"**Plots Enabled:** {self._enable_live_plots}\n" - + # Additional metadata for key, value in self._metadata.items(): if key not in ["physics_backend", "num_envs"]: metadata_text += f"**{key}:** {value}\n" - + # Log to Rerun rr.log("metadata", rr.TextDocument(metadata_text, media_type=rr.MediaType.MARKDOWN)) - - def register_markers(self, markers: Any) -> None: - """Register VisualizationMarkers for active logging. - - Args: - markers: VisualizationMarkers instance to log each frame. - """ - if self._enable_markers: - self._registered_markers.append(markers) - omni.log.info(f"[RerunVisualizer] Registered markers: {markers}") - - def register_plots(self, plots: dict[str, Any]) -> None: - """Register LivePlot instances for active logging. - - Args: - plots: Dictionary mapping plot names to LivePlot instances. - """ - if self._enable_live_plots: - self._registered_plots.update(plots) - omni.log.info(f"[RerunVisualizer] Registered {len(plots)} plot(s)") - - def log_markers(self) -> None: - """Log registered VisualizationMarkers to Rerun. - - Converts Isaac Lab markers to Rerun primitives (arrows, frames, spheres). - """ - if not self._enable_markers or len(self._registered_markers) == 0: - return - - try: - for marker_idx, markers in enumerate(self._registered_markers): - # Check if markers object has data access methods - if not hasattr(markers, 'data'): - continue - - marker_data = markers.data - entity_path = f"markers/{markers.__class__.__name__}_{marker_idx}" - - # Log arrows as line segments - if hasattr(marker_data, 'arrows') and marker_data.arrows is not None: - arrows = marker_data.arrows - if hasattr(arrows, 'positions') and hasattr(arrows, 'directions'): - positions = arrows.positions.cpu().numpy() if hasattr(arrows.positions, 'cpu') else arrows.positions - directions = arrows.directions.cpu().numpy() if hasattr(arrows.directions, 'cpu') else arrows.directions - - if len(positions) > 0: - # Create line segments from position to position+direction - for i in range(len(positions)): - start = positions[i] - end = start + directions[i] - rr.log(f"{entity_path}/arrow_{i}", rr.Arrows3D( - origins=[start], - vectors=[directions[i]] - )) - - # Log spheres as 3D points with radii - if hasattr(marker_data, 'spheres') and marker_data.spheres is not None: - spheres = marker_data.spheres - if hasattr(spheres, 'positions'): - positions = spheres.positions.cpu().numpy() if hasattr(spheres.positions, 'cpu') else spheres.positions - radii = spheres.radii.cpu().numpy() if hasattr(spheres, 'radii') else [0.05] * len(positions) - - if len(positions) > 0: - rr.log(f"{entity_path}/spheres", rr.Points3D( - positions=positions, - radii=radii - )) - - # Log coordinate frames as transform axes - if hasattr(marker_data, 'frames') and marker_data.frames is not None: - frames = marker_data.frames - if hasattr(frames, 'positions') and hasattr(frames, 'orientations'): - positions = frames.positions.cpu().numpy() if hasattr(frames.positions, 'cpu') else frames.positions - orientations = frames.orientations.cpu().numpy() if hasattr(frames.orientations, 'cpu') else frames.orientations - scale = frames.scale if hasattr(frames, 'scale') else 0.1 - - for i in range(len(positions)): - # Log as transform with axes - rr.log(f"{entity_path}/frame_{i}", rr.Transform3D( - translation=positions[i], - rotation=rr.Quaternion(xyzw=orientations[i]), - axis_length=scale - )) - - except Exception as e: - omni.log.warn(f"[RerunVisualizer] Failed to log markers: {e}") - - def log_plot_data(self) -> None: - """Log registered LivePlot data to Rerun as time series scalars.""" - if not self._enable_live_plots or len(self._registered_plots) == 0: - return - - try: - for plot_name, plot_obj in self._registered_plots.items(): - # Try to extract data from common plot object attributes - data_value = None - - # Method 1: Check for 'value' or 'data' attribute - if hasattr(plot_obj, 'value'): - data_value = plot_obj.value - elif hasattr(plot_obj, 'data'): - data_value = plot_obj.data - - # Method 2: Check for get_data() or get_value() methods - elif hasattr(plot_obj, 'get_data'): - data_value = plot_obj.get_data() - elif hasattr(plot_obj, 'get_value'): - data_value = plot_obj.get_value() - - # Method 3: Check for buffer/history attribute (get latest value) - elif hasattr(plot_obj, 'buffer') and plot_obj.buffer is not None: - if len(plot_obj.buffer) > 0: - data_value = plot_obj.buffer[-1] - elif hasattr(plot_obj, 'history') and plot_obj.history is not None: - if len(plot_obj.history) > 0: - data_value = plot_obj.history[-1] - - # Log the scalar value if we found it - if data_value is not None: - # Convert tensor to scalar if needed - if hasattr(data_value, 'item'): - data_value = data_value.item() - elif hasattr(data_value, 'cpu'): - data_value = data_value.cpu().numpy() - - # Handle numpy arrays (take mean if multi-dimensional) - if isinstance(data_value, np.ndarray): - if data_value.size == 1: - data_value = float(data_value.flat[0]) - else: - data_value = float(np.mean(data_value)) - - # Log as scalar - rr.log(f"plots/{plot_name}", rr.Scalar(float(data_value))) - - except Exception as e: - omni.log.warn(f"[RerunVisualizer] Failed to log plot data: {e}") - class RerunVisualizer(Visualizer): """Rerun web-based visualizer with time scrubbing, recording, and data inspection. - + Requires Newton physics backend and rerun-sdk (pip install rerun-sdk).""" def __init__(self, cfg: RerunVisualizerCfg): """Initialize Rerun visualizer.""" super().__init__(cfg) self.cfg: RerunVisualizerCfg = cfg - + if not _RERUN_AVAILABLE: raise ImportError("Rerun visualizer requires rerun-sdk and Newton. Install: pip install rerun-sdk") - + self._viewer: NewtonViewerRerun | None = None self._model = None self._state = None self._is_initialized = False self._sim_time = 0.0 self._scene_data_provider = None - + def initialize(self, scene_data: dict[str, Any] | None = None) -> None: """Initialize visualizer with Newton Model and State.""" if self._is_initialized: omni.log.warn("[RerunVisualizer] Already initialized. Skipping re-initialization.") return - + # Import NewtonManager for metadata access from isaaclab.sim._impl.newton_manager import NewtonManager - + # Store scene data provider for accessing physics state if scene_data and "scene_data_provider" in scene_data: self._scene_data_provider = scene_data["scene_data_provider"] - + # Get Newton-specific data from scene data provider if self._scene_data_provider: self._model = self._scene_data_provider.get_model() @@ -279,20 +129,17 @@ def initialize(self, scene_data: dict[str, Any] | None = None) -> None: # Fallback: direct access to NewtonManager (for backward compatibility) self._model = NewtonManager._model self._state = NewtonManager._state_0 - + # Validate required Newton data if self._model is None: raise RuntimeError( "Rerun visualizer requires a Newton Model. " "Make sure Newton physics is initialized before creating the visualizer." ) - + if self._state is None: - omni.log.warn( - "[RerunVisualizer] No Newton State available. " - "Visualization may not work correctly." - ) - + omni.log.warn("[RerunVisualizer] No Newton State available. Visualization may not work correctly.") + # Build metadata from NewtonManager metadata = { "physics_backend": "newton", @@ -300,12 +147,12 @@ def initialize(self, scene_data: dict[str, Any] | None = None) -> None: "gravity_vector": NewtonManager._gravity_vector, "clone_physics_only": NewtonManager._clone_physics_only, } - + # Create Newton ViewerRerun wrapper try: if self.cfg.record_to_rrd: omni.log.info(f"[RerunVisualizer] Recording enabled to: {self.cfg.record_to_rrd}") - + self._viewer = NewtonViewerRerun( server=self.cfg.server_mode, address=self.cfg.server_address, @@ -315,38 +162,31 @@ def initialize(self, scene_data: dict[str, Any] | None = None) -> None: keep_scalar_history=self.cfg.keep_scalar_history, record_to_rrd=self.cfg.record_to_rrd, metadata=metadata, - enable_markers=self.cfg.enable_markers, - enable_live_plots=self.cfg.enable_live_plots, ) - + # Set the model self._viewer.set_model(self._model) - - # TODO: Partial visualization will be implemented through a new cloner feature - + # Log initialization num_envs = metadata.get("num_envs", 0) physics_backend = metadata.get("physics_backend", "newton") - omni.log.info( - f"[RerunVisualizer] Initialized with {num_envs} environments " - f"(physics: {physics_backend})" - ) - + omni.log.info(f"[RerunVisualizer] Initialized with {num_envs} environments (physics: {physics_backend})") + self._is_initialized = True - + except Exception as e: omni.log.error(f"[RerunVisualizer] Failed to initialize viewer: {e}") raise - + def step(self, dt: float, state: Any | None = None) -> None: """Update visualizer each step. - + This method: 1. Fetches updated state from NewtonManager 2. Logs current state to Rerun (transforms, meshes) 3. Actively logs markers (if enabled) 4. Actively logs plot data (if enabled) - + Args: dt: Time step in seconds. state: Unused (deprecated parameter, kept for API compatibility). @@ -354,41 +194,34 @@ def step(self, dt: float, state: Any | None = None) -> None: if not self._is_initialized or self._viewer is None: omni.log.warn("[RerunVisualizer] Not initialized. Call initialize() first.") return - + # Fetch updated state from scene data provider if self._scene_data_provider: self._state = self._scene_data_provider.get_state() else: # Fallback: direct access to NewtonManager from isaaclab.sim._impl.newton_manager import NewtonManager + self._state = NewtonManager._state_0 - + # Update internal time self._sim_time += dt - + # Begin frame with current simulation time self._viewer.begin_frame(self._sim_time) - + # Log state (transforms) - Newton's ViewerRerun handles this if self._state is not None: self._viewer.log_state(self._state) - - # Actively log markers (if enabled) - if self.cfg.enable_markers: - self._viewer.log_markers() - - # Actively log plot data (if enabled) - if self.cfg.enable_live_plots: - self._viewer.log_plot_data() - + # End frame self._viewer.end_frame() - + def close(self) -> None: """Clean up Rerun visualizer resources and finalize recordings.""" if not self._is_initialized or self._viewer is None: return - + try: if self.cfg.record_to_rrd: omni.log.info(f"[RerunVisualizer] Finalizing recording to: {self.cfg.record_to_rrd}") @@ -396,6 +229,7 @@ def close(self) -> None: omni.log.info("[RerunVisualizer] Closed successfully.") if self.cfg.record_to_rrd: import os + if os.path.exists(self.cfg.record_to_rrd): size = os.path.getsize(self.cfg.record_to_rrd) omni.log.info(f"[RerunVisualizer] Recording saved: {self.cfg.record_to_rrd} ({size} bytes)") @@ -403,64 +237,32 @@ def close(self) -> None: omni.log.warn(f"[RerunVisualizer] Recording file not found: {self.cfg.record_to_rrd}") except Exception as e: omni.log.warn(f"[RerunVisualizer] Error during close: {e}") - + self._viewer = None self._is_initialized = False - + def is_running(self) -> bool: """Check if visualizer is running. - + Returns: True if viewer is initialized and running, False otherwise. """ if self._viewer is None: return False return self._viewer.is_running() - + def is_training_paused(self) -> bool: """Check if training is paused. - + Note: - Rerun visualizer uses Rerun's built-in timeline controls for playback. - It does not provide a training pause mechanism like NewtonVisualizer. - - Returns: - False - Rerun does not support training pause. + Rerun visualizer currently uses Rerun's built-in timeline controls for playback. """ return False - + def supports_markers(self) -> bool: - """Check if this visualizer supports visualization markers. - - Returns: - True - Rerun supports markers via active logging. - """ - return True - - def supports_live_plots(self) -> bool: - """Check if this visualizer supports live plots. - - Returns: - True - Rerun supports plots via active logging (currently stub). - """ - return True - - def register_markers(self, markers: Any) -> None: - """Register VisualizationMarkers for active logging. - - Args: - markers: VisualizationMarkers instance to visualize. - """ - if self._viewer: - self._viewer.register_markers(markers) - - def register_plots(self, plots: dict[str, Any]) -> None: - """Register LivePlot instances for active logging. - - Args: - plots: Dictionary mapping plot names to LivePlot instances. - """ - if self._viewer: - self._viewer.register_plots(plots) - + """Rerun visualizer does not have this feature yet.""" + return False + def supports_live_plots(self) -> bool: + """Rerun visualizer does not have this feature yet.""" + return False diff --git a/source/isaaclab/isaaclab/visualizers/rerun_visualizer_cfg.py b/source/isaaclab/isaaclab/visualizers/rerun_visualizer_cfg.py index aacae6aa3a6..b91c71b8e9e 100644 --- a/source/isaaclab/isaaclab/visualizers/rerun_visualizer_cfg.py +++ b/source/isaaclab/isaaclab/visualizers/rerun_visualizer_cfg.py @@ -1,3 +1,8 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + # Copyright (c) 2022-2025, The Isaac Lab Project Developers. # All rights reserved. # @@ -15,7 +20,7 @@ @configclass class RerunVisualizerCfg(VisualizerCfg): """Configuration for Rerun visualizer (web-based visualization). - + Provides time scrubbing, 3D navigation, data filtering, and .rrd recording. Requires Newton physics backend and rerun-sdk: `pip install rerun-sdk` """ @@ -43,4 +48,3 @@ class RerunVisualizerCfg(VisualizerCfg): record_to_rrd: str | None = None """Path to save .rrd recording file. None = no recording.""" - diff --git a/source/isaaclab/isaaclab/visualizers/visualizer.py b/source/isaaclab/isaaclab/visualizers/visualizer.py index 3ff45ef35df..1fef125d52c 100644 --- a/source/isaaclab/isaaclab/visualizers/visualizer.py +++ b/source/isaaclab/isaaclab/visualizers/visualizer.py @@ -16,7 +16,7 @@ class Visualizer(ABC): """Base class for all visualizer backends. - + Lifecycle: __init__() -> initialize() -> step() (repeated) -> close() """ @@ -34,7 +34,7 @@ def initialize(self, scene_data: dict[str, Any] | None = None) -> None: @abstractmethod def step(self, dt: float, state: Any | None = None) -> None: """Update visualization for one step. - + Args: dt: Time step in seconds. state: Updated physics state (e.g., newton.State). @@ -68,12 +68,11 @@ def is_initialized(self) -> bool: def is_closed(self) -> bool: """Check if close() has been called.""" return self._is_closed - + def supports_markers(self) -> bool: """Check if visualizer supports VisualizationMarkers.""" return False - + def supports_live_plots(self) -> bool: """Check if visualizer supports LivePlots.""" return False - diff --git a/source/isaaclab/isaaclab/visualizers/visualizer_cfg.py b/source/isaaclab/isaaclab/visualizers/visualizer_cfg.py index 33822a2bcee..100411c3061 100644 --- a/source/isaaclab/isaaclab/visualizers/visualizer_cfg.py +++ b/source/isaaclab/isaaclab/visualizers/visualizer_cfg.py @@ -7,7 +7,7 @@ from __future__ import annotations -from typing import TYPE_CHECKING, Literal +from typing import TYPE_CHECKING from isaaclab.utils import configclass @@ -22,21 +22,20 @@ class VisualizerCfg: visualizer_type: str = "base" """Type identifier (e.g., 'newton', 'rerun', 'omniverse').""" - # TODO: Partial visualization will be implemented through a new cloner feature - # that allows filtering environments at the simulation level rather than per-visualizer. - # This approach will be more efficient and consistent across all visualizers. + # Note: Partial environment visualization will come later + # env_ids: list[Integer] = [] enable_markers: bool = True """Enable visualization markers (debug drawing).""" enable_live_plots: bool = True """Enable live plotting of data. - + When set to True for OVVisualizer: - Automatically checks the checkboxes for all manager visualizers (Actions, Observations, Rewards, etc.) - Keeps the plot frames expanded by default (not collapsed) - Makes the live plots visible immediately in the IsaacLab window (docked to the right of the viewport) - + This provides a better out-of-the-box experience when you want to monitor training metrics. """ @@ -51,7 +50,5 @@ def create_visualizer(self) -> Visualizer: visualizer_class = get_visualizer_class(self.visualizer_type) if visualizer_class is None: raise ValueError(f"Visualizer type '{self.visualizer_type}' is not registered.") - - return visualizer_class(self) - + return visualizer_class(self) diff --git a/source/isaaclab/setup.py b/source/isaaclab/setup.py index d12b156a505..bf12b70644d 100644 --- a/source/isaaclab/setup.py +++ b/source/isaaclab/setup.py @@ -51,11 +51,11 @@ "mujoco>=3.3.8.dev821851540", "mujoco-warp @ git+https://github.com/google-deepmind/mujoco_warp.git@bbd757cace561de47512b560517ee728c8416de5", "newton @ git+https://github.com/newton-physics/newton.git@15b9955bafa61f8fcb40c17dc00f0b552d3c65ca", - # "newton @ git+https://github.com/newton-physics/newton.git@c4baa06c3e8ea0a3090037b2b197e9aa453265f1", "imgui-bundle==1.92.0", "PyOpenGL-accelerate==3.1.10", - # visualizers - "rerun-sdk", + # Note, this older version of rerun causes the view to flash dark & light + # newer versions of rerun, like 0.27, don't have this issue, but require numpy >=2 + "rerun-sdk==0.23", ] # Additional dependencies that are only available on Linux platforms diff --git a/source/isaaclab_tasks/isaaclab_tasks/utils/parse_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/utils/parse_cfg.py index 212640e1918..15c33f9121c 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/utils/parse_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/utils/parse_cfg.py @@ -136,7 +136,7 @@ def parse_env_cfg( Raises: RuntimeError: If the configuration for the task is not a class. We assume users always use a class for the environment configuration. - + Note: Visualizer configuration should be done via Hydra command line arguments. Example: ``env.sim.visualizer_cfgs=isaaclab.visualizers:NewtonVisualizerCfg`` From ecb66affcf3876271106e9ce225a89e763db9b0a Mon Sep 17 00:00:00 2001 From: mtrepte Date: Fri, 21 Nov 2025 15:29:16 -0800 Subject: [PATCH 21/24] clean before review --- source/isaaclab/isaaclab/sim/__init__.py | 2 +- .../isaaclab/isaaclab/sim/simulation_cfg.py | 7 +++-- .../isaaclab/sim/simulation_context.py | 27 ------------------- .../isaaclab_tasks/utils/parse_cfg.py | 4 --- 4 files changed, 4 insertions(+), 36 deletions(-) diff --git a/source/isaaclab/isaaclab/sim/__init__.py b/source/isaaclab/isaaclab/sim/__init__.py index ce3a3a16c24..6819cacf87b 100644 --- a/source/isaaclab/isaaclab/sim/__init__.py +++ b/source/isaaclab/isaaclab/sim/__init__.py @@ -29,6 +29,6 @@ from .converters import * # noqa: F401, F403 from .schemas import * # noqa: F401, F403 from .simulation_cfg import RenderCfg, SimulationCfg # noqa: F401, F403 -from .simulation_context import SimulationContext, build_simulation_context, enable_visualizers # noqa: F401, F403 +from .simulation_context import SimulationContext, build_simulation_context # noqa: F401, F403 from .spawners import * # noqa: F401, F403 from .utils import * # noqa: F401, F403 diff --git a/source/isaaclab/isaaclab/sim/simulation_cfg.py b/source/isaaclab/isaaclab/sim/simulation_cfg.py index fb5bf6b1bba..45e8821a24e 100644 --- a/source/isaaclab/isaaclab/sim/simulation_cfg.py +++ b/source/isaaclab/isaaclab/sim/simulation_cfg.py @@ -197,13 +197,12 @@ class SimulationCfg: render_cfg: RenderCfg = RenderCfg() """Render settings. Default is RenderCfg().""" - # visualizer_cfgs: list[VisualizerCfg] | VisualizerCfg | None = NewtonVisualizerCfg() visualizer_cfgs: list[VisualizerCfg] | VisualizerCfg | None = [ - OVVisualizerCfg(), NewtonVisualizerCfg(), + OVVisualizerCfg(), RerunVisualizerCfg(), - ] - """Visualizer settings. Default is NewtonVisualizerCfg(). + ] # None + """Visualizer settings. Default is no visualizer. This field supports multiple visualizer backends for debug visualization and monitoring during simulation. It accepts: diff --git a/source/isaaclab/isaaclab/sim/simulation_context.py b/source/isaaclab/isaaclab/sim/simulation_context.py index 4d959919cab..d716e482eea 100644 --- a/source/isaaclab/isaaclab/sim/simulation_context.py +++ b/source/isaaclab/isaaclab/sim/simulation_context.py @@ -1029,30 +1029,3 @@ def build_simulation_context( exception_to_raise = builtins.ISAACLAB_CALLBACK_EXCEPTION builtins.ISAACLAB_CALLBACK_EXCEPTION = None raise exception_to_raise - - -def enable_visualizers(env_cfg, train_mode: bool = True) -> None: - """Enable visualizers for an environment configuration. - - Sets visualizers to Newton OpenGL if none configured, and sets train_mode. - - Args: - env_cfg: Environment configuration (DirectRLEnvCfg or ManagerBasedRLEnvCfg) to modify. - train_mode: Whether to run visualizers in training mode (True) or play/inference mode (False). - - Example: - >>> import isaaclab.sim as sim_utils - >>> if args_cli.visualize: - ... sim_utils.enable_visualizers(env_cfg) - """ - from isaaclab.visualizers import NewtonVisualizerCfg - - if env_cfg.sim.visualizer_cfgs is None: - env_cfg.sim.visualizer_cfgs = NewtonVisualizerCfg() - - # Set train_mode on all configured visualizers - if isinstance(env_cfg.sim.visualizer_cfgs, list): - for viz_cfg in env_cfg.sim.visualizer_cfgs: - viz_cfg.train_mode = train_mode - else: - env_cfg.sim.visualizer_cfgs.train_mode = train_mode diff --git a/source/isaaclab_tasks/isaaclab_tasks/utils/parse_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/utils/parse_cfg.py index 15c33f9121c..a07befbd3f9 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/utils/parse_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/utils/parse_cfg.py @@ -136,10 +136,6 @@ def parse_env_cfg( Raises: RuntimeError: If the configuration for the task is not a class. We assume users always use a class for the environment configuration. - - Note: - Visualizer configuration should be done via Hydra command line arguments. - Example: ``env.sim.visualizer_cfgs=isaaclab.visualizers:NewtonVisualizerCfg`` """ # load the default configuration cfg = load_cfg_from_registry(task_name.split(":")[-1], "env_cfg_entry_point") From 7562067254948b35507a3d951a32f659f8331db4 Mon Sep 17 00:00:00 2001 From: mtrepte Date: Fri, 21 Nov 2025 15:30:08 -0800 Subject: [PATCH 22/24] default to no viz --- source/isaaclab/isaaclab/sim/simulation_cfg.py | 6 +----- 1 file changed, 1 insertion(+), 5 deletions(-) diff --git a/source/isaaclab/isaaclab/sim/simulation_cfg.py b/source/isaaclab/isaaclab/sim/simulation_cfg.py index 45e8821a24e..aeb6e5cff37 100644 --- a/source/isaaclab/isaaclab/sim/simulation_cfg.py +++ b/source/isaaclab/isaaclab/sim/simulation_cfg.py @@ -197,11 +197,7 @@ class SimulationCfg: render_cfg: RenderCfg = RenderCfg() """Render settings. Default is RenderCfg().""" - visualizer_cfgs: list[VisualizerCfg] | VisualizerCfg | None = [ - NewtonVisualizerCfg(), - OVVisualizerCfg(), - RerunVisualizerCfg(), - ] # None + visualizer_cfgs: list[VisualizerCfg] | VisualizerCfg | None = None """Visualizer settings. Default is no visualizer. This field supports multiple visualizer backends for debug visualization and monitoring From 52ae2f3c6393ca845106c5e4875e699612ef8ef7 Mon Sep 17 00:00:00 2001 From: matthewtrepte Date: Fri, 21 Nov 2025 15:35:52 -0800 Subject: [PATCH 23/24] Update simulation_cfg.py Signed-off-by: matthewtrepte --- source/isaaclab/isaaclab/sim/simulation_cfg.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/source/isaaclab/isaaclab/sim/simulation_cfg.py b/source/isaaclab/isaaclab/sim/simulation_cfg.py index aeb6e5cff37..528fd7daead 100644 --- a/source/isaaclab/isaaclab/sim/simulation_cfg.py +++ b/source/isaaclab/isaaclab/sim/simulation_cfg.py @@ -207,9 +207,9 @@ class SimulationCfg: - None or empty list: No visualizers will be created Supported visualizer backends: - - NewtonVisualizerCfg: Lightweight OpenGL-based visualizer (default) + - NewtonVisualizerCfg: Lightweight OpenGL-based visualizer - OVVisualizerCfg: Omniverse-based high-fidelity visualizer - - RerunVisualizerCfg: Web-based Rerun visualizer + - RerunVisualizerCfg: Web-based Rerun visualizer with recording and replay Examples: # Disable all visualizers From 17aa1e58900c5b1acc99568801c244cde1fb4528 Mon Sep 17 00:00:00 2001 From: matthewtrepte Date: Fri, 21 Nov 2025 15:37:39 -0800 Subject: [PATCH 24/24] Update simulation_cfg.py Signed-off-by: matthewtrepte --- source/isaaclab/isaaclab/sim/simulation_cfg.py | 10 +++------- 1 file changed, 3 insertions(+), 7 deletions(-) diff --git a/source/isaaclab/isaaclab/sim/simulation_cfg.py b/source/isaaclab/isaaclab/sim/simulation_cfg.py index 528fd7daead..45dec51eee5 100644 --- a/source/isaaclab/isaaclab/sim/simulation_cfg.py +++ b/source/isaaclab/isaaclab/sim/simulation_cfg.py @@ -200,8 +200,9 @@ class SimulationCfg: visualizer_cfgs: list[VisualizerCfg] | VisualizerCfg | None = None """Visualizer settings. Default is no visualizer. - This field supports multiple visualizer backends for debug visualization and monitoring - during simulation. It accepts: + Visualizers are separate from Renderers and intended for light-weight monitoring and debugging. + + This field can support multiple visualizer backends. It accepts: - A single VisualizerCfg: One visualizer will be created - A list of VisualizerCfg: Multiple visualizers will be created - None or empty list: No visualizers will be created @@ -228,11 +229,6 @@ class SimulationCfg: NewtonVisualizerCfg(camera_position=(10.0, 0.0, 3.0)), RerunVisualizerCfg(server_address="127.0.0.1:9876") ]) - - Note: - Visualizers are separate from rendering backends (for cameras/sensors). - They are intended for debug visualization and monitoring only. - Visualizers are automatically initialized in SimulationContext during reset(). """ create_stage_in_memory: bool = False