diff --git a/examples/gui/imgui_joint_control.py b/examples/gui/imgui_joint_control.py index cd39449f4..3e1ab6efe 100644 --- a/examples/gui/imgui_joint_control.py +++ b/examples/gui/imgui_joint_control.py @@ -47,7 +47,7 @@ scene.build() # Grab the auto-attached overlay to register a custom panel. -plugin = next(p for p in scene.viewer._viewer_plugins if isinstance(p, ImGuiOverlayPlugin)) +plugin = next(p for p in scene.viewer.plugins if isinstance(p, ImGuiOverlayPlugin)) def custom_panel(imgui): diff --git a/genesis/_main.py b/genesis/_main.py index 9b9457a17..db3d6a484 100644 --- a/genesis/_main.py +++ b/genesis/_main.py @@ -1,250 +1,27 @@ import argparse -import multiprocessing -from functools import partial - -import tkinter as tk -from tkinter import ttk import numpy as np -import torch import genesis as gs +from genesis.ext.pyrender.overlay import ImGuiOverlayPlugin FPS = 60 -class JointControlGUI: - def __init__(self, master, display_items, motors_position_limit, motors_position): - self.master = master - self.master.title("Joint Controller") # Set the window title - self.display_items = display_items - self.motors_position_limit = motors_position_limit - self.motors_position = motors_position - n_dofs = len(motors_position_limit) - self.motors_default_position = np.clip( - np.zeros(n_dofs), motors_position_limit[:, 0], motors_position_limit[:, 1] - ) - self.sliders = [] - self.values_label = [] - self.create_widgets() - self.reset_motors_position() - - def create_widgets(self): - container = tk.Frame(self.master) - container.pack(fill=tk.BOTH, expand=True) - - canvas = tk.Canvas(container, borderwidth=0, highlightthickness=0) - scrollbar = ttk.Scrollbar(container, orient=tk.VERTICAL) - scrollbar.pack(side=tk.RIGHT, fill=tk.Y) - canvas.pack(side=tk.LEFT, fill=tk.BOTH, expand=True) - - def on_yscrollcommand(*args): - canvas.update_idletasks() - top, bot = canvas.yview() - if top < 0: - canvas.yview_moveto(0) - scrollbar.set(*canvas.yview()) - - canvas.configure(yscrollcommand=on_yscrollcommand) - scrollbar.configure(command=canvas.yview) - - scrollable_frame = tk.Frame(canvas) - window_id = canvas.create_window((0, 0), window=scrollable_frame, anchor="nw") - - def update_scroll_region_and_bar(): - bbox = canvas.bbox("all") - if bbox: - w = max(bbox[2] - bbox[0], 1) - h = max(bbox[3] - bbox[1], 1) - canvas.configure(scrollregion=(0, 0, w, h)) - content_h = h - canvas.update_idletasks() - canvas_h = canvas.winfo_height() - if content_h > canvas_h: - scrollbar.pack(side=tk.RIGHT, fill=tk.Y) - else: - scrollbar.pack_forget() - canvas.yview_moveto(0) - - def on_frame_configure(event): - update_scroll_region_and_bar() - - def on_canvas_configure(event): - canvas.itemconfig(window_id, width=event.width) - update_scroll_region_and_bar() - - scrollable_frame.bind("", on_frame_configure) - canvas.bind("", on_canvas_configure) - - def on_mousewheel(event): - if not event.delta: - return - canvas.update_idletasks() - if not scrollbar.winfo_ismapped(): - return - canvas.yview_scroll(int(-1 * (event.delta / 120)), "units") - if canvas.yview()[0] < 0: - canvas.yview_moveto(0) - - def on_linux_scroll(event): - canvas.update_idletasks() - if not scrollbar.winfo_ismapped(): - return - if event.num == 4: - canvas.yview_scroll(-1, "units") - elif event.num == 5: - canvas.yview_scroll(1, "units") - if canvas.yview()[0] < 0: - canvas.yview_moveto(0) - - canvas.bind_all("", on_mousewheel) - canvas.bind_all("", on_linux_scroll) - canvas.bind_all("", on_linux_scroll) - - slider_idx = 0 - for label, is_delimiter in self.display_items: - frame = tk.Frame(scrollable_frame) - if is_delimiter: - frame.pack(pady=(12, 4), padx=10, fill=tk.X) - sep = ttk.Separator(scrollable_frame, orient=tk.HORIZONTAL) - sep.pack(fill=tk.X, padx=10, pady=(0, 2)) - tk.Label(frame, text=label, font=("Arial", 12, "bold")).pack() - continue - frame.pack(pady=5, padx=10, fill=tk.X) - self.update_joint_position(slider_idx, self.motors_default_position[slider_idx]) - min_limit, max_limit = map(float, self.motors_position_limit[slider_idx]) - tk.Label(frame, text=label, font=("Arial", 12), anchor=tk.W).pack(side=tk.LEFT) - value_label = tk.Label(frame, text="0.00", font=("Arial", 12)) - value_label.pack(side=tk.RIGHT, padx=(5, 0)) - slider = ttk.Scale( - frame, - from_=min_limit, - to=max_limit, - orient=tk.HORIZONTAL, - command=partial(self.update_joint_position, slider_idx), - ) - slider.pack(side=tk.LEFT, fill=tk.X, expand=True, padx=5) - slider.set(self.motors_default_position[slider_idx]) - value_label.config(text=f"{slider.get():.2f}") - self.sliders.append(slider) - self.values_label.append(value_label) - - # Update label dynamically - def update_label(s=slider, l=value_label): - def callback(event): - l.config(text=f"{s.get():.2f}") - - return callback - - slider.bind("", update_label()) - slider_idx += 1 - - tk.Button(scrollable_frame, text="Reset", font=("Arial", 12), command=self.reset_motors_position).pack(pady=20) - - def update_joint_position(self, idx, val): - self.motors_position[idx] = float(val) - - def reset_motors_position(self): - for i_m, slider in enumerate(self.sliders): - slider.set(self.motors_default_position[i_m]) - self.values_label[i_m].config(text=f"{self.motors_default_position[i_m]:.2f}") - self.motors_position[i_m] = self.motors_default_position[i_m] - - -def get_motors_info(robot): - motors_dof_idx = [] - motors_dof_name = [] - for joint in robot.joints: - if joint.type == gs.JOINT_TYPE.FREE: - continue - elif joint.type == gs.JOINT_TYPE.FIXED: - continue - dofs_idx_local = robot.get_joint(joint.name).dofs_idx_local - if dofs_idx_local: - if len(dofs_idx_local) == 1: - dofs_name = [joint.name] - else: - dofs_name = [f"{joint.name}_{i_d}" for i_d in dofs_idx_local] - motors_dof_idx += dofs_idx_local - motors_dof_name += dofs_name - return motors_dof_idx, motors_dof_name - - -def get_motors_info_for_view(entities): - if not hasattr(entities, "__iter__") or hasattr(entities, "joints"): - entities = [entities] - entity_specs = [] - for entity in entities: - motors_dof_idx, motors_dof_name = get_motors_info(entity) - if motors_dof_idx: - entity_specs.append((entity, motors_dof_idx, motors_dof_name)) - if not entity_specs: - return [], [], np.zeros((0, 2), dtype=np.float64) - - display_items = [] - all_limits = [] - entity_dof_specs = [] - n_entities_in_scene = len(entities) - for i, (entity, dofs_idx, names) in enumerate(entity_specs): - if n_entities_in_scene > 1: - display_items.append((f"——— {entity.name} ———", True)) - for name in names: - display_items.append((name, False)) - entity_dof_specs.append((entity, dofs_idx)) - limits = torch.stack(entity.get_dofs_limit(dofs_idx), dim=1).numpy() - limits[limits == -np.inf] = -np.pi - limits[limits == np.inf] = np.pi - all_limits.append(limits) - motors_position_limit = np.vstack(all_limits) - return display_items, entity_dof_specs, motors_position_limit - - -def _start_gui(display_items, motors_position_limit, motors_position, stop_event): - def on_close(): - nonlocal after_id - if after_id is not None: - root.after_cancel(after_id) - after_id = None - stop_event.set() - root.destroy() - root.quit() - - root = tk.Tk() - root.minsize(520, 400) - - # Size window so content fits without vertical scroll when possible - row_heights = [50 if is_delimiter else 36 for _, is_delimiter in display_items] - content_h = sum(row_heights) + 100 # + reset button and padding - screen_h = root.winfo_screenheight() - height = min(content_h, max(400, screen_h - 120)) - root.geometry(f"560x{height}") - - # Store joint control gui to make sure it does not get garbage collected, just in case, because it may break tkinter - _app = JointControlGUI(root, display_items, motors_position_limit, motors_position) - - root.protocol("WM_DELETE_WINDOW", on_close) - - def check_event(): - nonlocal after_id - if stop_event.is_set(): - on_close() - elif root.winfo_exists(): - after_id = root.after(100, check_event) - - after_id = root.after(100, check_event) - root.mainloop() - - -def view(filename, collision, rotate, scale=1.0, show_link_frame=False): +def launch(filename, collision, rotate, scale=1.0, show_link_frame=False, deprecated=False): gs.init(backend=gs.cpu) + if deprecated: + gs.logger.warning("'gs view' is deprecated and will be removed in a future release. Use 'gs launch' instead.") + scene = gs.Scene( viewer_options=gs.options.ViewerOptions( camera_pos=(3.5, 0.0, 2.5), camera_lookat=(0.0, 0.0, 0.5), camera_fov=40, max_FPS=FPS, + enable_gui=True, ), vis_options=gs.options.VisOptions( show_link_frame=show_link_frame, @@ -255,7 +32,7 @@ def view(filename, collision, rotate, scale=1.0, show_link_frame=False): filename_lower = filename.lower() morphs = gs.options.morphs - material = gs.materials.Kinematic() + material = gs.materials.Rigid() surface = gs.surfaces.Default(vis_mode="visual" if not collision else "collision") if filename_lower.endswith(morphs.USD_FORMATS): @@ -296,57 +73,31 @@ def view(filename, collision, rotate, scale=1.0, show_link_frame=False): scene.build(compile_kernels=False) - display_items, entity_dof_specs, motors_position_limit = get_motors_info_for_view(entities) - total_dofs = len(motors_position_limit) - - # Start the GUI process - if total_dofs > 0: - manager = multiprocessing.Manager() - motors_position = manager.list([0.0] * total_dofs) - stop_event = multiprocessing.Event() - gui_process = multiprocessing.Process( - target=_start_gui, - args=(display_items, motors_position_limit, motors_position, stop_event), - daemon=True, - ) - gui_process.start() - else: - stop_event = multiprocessing.Event() + # 'enable_gui=True' auto-attaches the ImGui overlay, which owns the simulation through an InteractiveScene: + # play/pause/step/reset and per-joint sliders (editable while paused) live in the overlay. Start paused so the + # asset can be inspected and posed before the physics simulation is stepped. + plugin = next(p for p in scene.viewer.plugins if isinstance(p, ImGuiOverlayPlugin)) + plugin.interactive_scene.pause() t = 0 - while scene.viewer.is_alive() and not stop_event.is_set(): - # Rotate entity if requested + while scene.viewer.is_alive(): + # Rotate entity if requested, independently of the play/pause state, as a visual turntable. if rotate: t += 1 / FPS quat = gs.utils.geom.xyz_to_quat(np.array([0, 0, t * 50]), rpy=True, degrees=True) for entity in entities: entity.set_quat(quat) - - if total_dofs > 0: - offset = 0 - for entity, dofs_idx in entity_dof_specs: - n = len(dofs_idx) - entity.set_dofs_position( - position=torch.tensor(motors_position[offset : offset + n]), - dofs_idx_local=dofs_idx, - zero_velocity=True, - ) - offset += n - scene.visualizer.update(force=True) - stop_event.set() - if total_dofs > 0: - gui_process.join() + scene.step() def play(filename=None, collision=False, scale=1.0): - import time - gs.init() scene = gs.Scene( viewer_options=gs.options.ViewerOptions( camera_pos=(2.0, 2.0, 1.5), camera_lookat=(0.0, 0.0, 0.5), + enable_gui=True, ), show_viewer=True, ) @@ -378,14 +129,8 @@ def play(filename=None, collision=False, scale=1.0): scene.build() - from genesis.ext.pyrender.overlay import ImGuiOverlayPlugin - - plugin = ImGuiOverlayPlugin() - scene.viewer.add_plugin(plugin) - while scene.viewer.is_alive(): scene.step() - time.sleep(0.01) def animate(filename_pattern, fps): @@ -406,14 +151,17 @@ def main(): parser = argparse.ArgumentParser(description="Genesis CLI") subparsers = parser.add_subparsers(dest="command") - parser_view = subparsers.add_parser("view", help="Visualize a given asset (Mesh/URDF/MJCF/USD)") - parser_view.add_argument("filename", type=str, help="File to visualize") - parser_view.add_argument( + launch_args = argparse.ArgumentParser(add_help=False) + launch_args.add_argument("filename", type=str, help="File to visualize") + launch_args.add_argument( "-c", "--collision", action="store_true", default=False, help="Whether to visualize collision geometry" ) - parser_view.add_argument("-r", "--rotate", action="store_true", default=False, help="Whether to rotate the entity") - parser_view.add_argument("-s", "--scale", type=float, default=1.0, help="Scale of the entity") - parser_view.add_argument("-l", "--link_frame", action="store_true", default=False, help="Show link frame") + launch_args.add_argument("-r", "--rotate", action="store_true", default=False, help="Whether to rotate the entity") + launch_args.add_argument("-s", "--scale", type=float, default=1.0, help="Scale of the entity") + launch_args.add_argument("-l", "--link_frame", action="store_true", default=False, help="Show link frame") + + subparsers.add_parser("launch", parents=[launch_args], help="Visualize a given asset (Mesh/URDF/MJCF/USD)") + subparsers.add_parser("view", parents=[launch_args], help="[DEPRECATED] Alias of 'launch'.") parser_play = subparsers.add_parser("play", help="Interactive viewer with ImGui joint controls and simulation") parser_play.add_argument( @@ -434,8 +182,15 @@ def main(): args = parser.parse_args() - if args.command == "view": - view(args.filename, args.collision, args.rotate, args.scale, args.link_frame) + if args.command in ("launch", "view"): + launch( + args.filename, + args.collision, + args.rotate, + args.scale, + args.link_frame, + deprecated=args.command == "view", + ) elif args.command == "play": play(args.filename, args.collision, args.scale) elif args.command == "animate": diff --git a/genesis/engine/interactive_scene.py b/genesis/engine/interactive_scene.py index 46ab4ad85..3c293484d 100644 --- a/genesis/engine/interactive_scene.py +++ b/genesis/engine/interactive_scene.py @@ -44,11 +44,12 @@ def __init__(self, scene: "Scene"): self._paused: bool = False self._pending_steps: int = 0 self._rebuild_pending: bool = False + self._reset_pending: bool = False self._entities_kwargs: dict[str, dict[str, Any]] = {} self._sensors_kwargs: list["SensorOptions"] = [] scene.register_pre_step_callback(self._pre_step) - # Capture the wrapped scene's construction so rebuild() can reconstruct it identically. The - # stored option objects are already merged with sim_options; re-passing them is idempotent. + # Capture the wrapped scene's construction so rebuild() can reconstruct it identically. The stored option + # objects are already merged with sim_options; re-passing them is idempotent. self._scene_kwargs: dict[str, Any] = dict( sim_options=scene.sim_options, coupler_options=scene.coupler_options, @@ -99,12 +100,18 @@ def step(self, n: int = 1) -> None: self._pending_steps += n def _pre_step(self) -> bool: - """Scene pre-step callback (runs on the stepping thread). Applies the queued intent and returns True to - skip the advance this frame: after performing a pending rebuild, or while paused with no queued steps.""" + """Scene pre-step callback that runs on the stepping thread. + + Applies the queued intent and returns True to skip the advance this frame: after performing a pending + rebuild or reset, or while paused with no queued steps.""" if self._rebuild_pending: self._rebuild_pending = False self._apply_rebuild() return True + if self._reset_pending: + self._reset_pending = False + self._apply_reset() + return True if self._pending_steps > 0: self._pending_steps -= 1 return False @@ -144,7 +151,7 @@ def is_built(self) -> bool: @property def _lock(self): - return self.scene.viewer.render_lock + return self.scene.viewer.lock @property def _ctx(self): @@ -166,9 +173,19 @@ def _refresh_visual_transforms_unlocked(self): ctx.update_link_frame() ctx.update_rigid() - @with_lock def reset(self): - """Reset the scene and refresh visuals. Clears contact arrows and other transient render nodes.""" + """Queue a reset of the wrapped scene to its initial state. + + Asynchronous: it is applied at the start of the next underlying step(), on the stepping thread, so it is + safe to call from a viewer-thread GUI callback. Applying it directly would re-enter the viewer refresh (and + thus the ImGui frame) from within the current frame.""" + self._reset_pending = True + + @with_lock + def _apply_reset(self): + """Reset the wrapped scene and refresh visuals, on the stepping thread. + + Clears contact arrows and other transient render nodes.""" self.scene.reset() self._ctx.clear_dynamic_nodes(only_outdated=False) self._refresh_visual_transforms_unlocked() @@ -282,17 +299,17 @@ def _apply_rebuild(self) -> None: if scene.viewer is not None: viewer = scene.viewer - # Capture the full 4x4 camera pose (position, lookat and roll/up), not just pos + lookat, so the - # user's current viewpoint is restored exactly across the rebuild instead of resetting the roll. + # Capture the full 4x4 camera pose (position, lookat and roll/up), not just pos + lookat, so the user's + # current viewpoint is restored exactly across the rebuild instead of resetting the roll. cam_pose = viewer.camera_pose.copy() # Skip default plugins; the rebuilt viewer recreates them based on its ViewerOptions. - plugins_to_reattach = [p for p in viewer._viewer_plugins if not isinstance(p, DefaultControlsPlugin)] + plugins_to_reattach = [p for p in viewer.plugins if not isinstance(p, DefaultControlsPlugin)] # Preserve the live window/GL context so the rebuild does not close and reopen it. pyrender_window = viewer._pyrender_viewer - # Serialize against a threaded render loop (run_in_thread=True): holding the preserved window's - # render_lock blocks on_draw so it never draws the scene while it is being torn down, rebuilt and - # re-pointed. No-op when there is no window (headless) or the viewer runs on the main thread. + # Serialize against a threaded render loop (run_in_thread=True): holding the preserved window's render_lock + # blocks on_draw so it never draws the scene while it is being torn down, rebuilt and re-pointed. No-op when + # there is no window (headless) or the viewer runs on the main thread. with pyrender_window.render_lock if pyrender_window is not None else contextlib.nullcontext(): if pyrender_window is not None: # Detach so scene.destroy() does not close the preserved window. @@ -313,18 +330,12 @@ def _apply_rebuild(self) -> None: new_viewer = scene.viewer if new_viewer is not None: - # A scene built with enable_gui=True auto-attaches its own ImGui overlay. When re-attaching the - # previous overlay (which carries user state - panel width, custom panels, pending edits), drop the - # fresh auto-attached one of the same type so the viewer does not end up with two overlays. The plugin - # must be cleared from both the wrapper staging list (_viewer_plugins) and pyrender's live list - # (plugins), since build() already copied it into the live render loop. + # A scene built with enable_gui=True auto-attaches its own ImGui overlay. When re-attaching the previous + # overlay (which carries user state - panel width, custom panels, pending edits), drop the fresh + # auto-attached one of the same type so the viewer does not end up with two overlays. reattach_types = {type(p) for p in plugins_to_reattach} - pyrender_viewer = new_viewer._pyrender_viewer - for plugin in [p for p in new_viewer._viewer_plugins if type(p) in reattach_types]: - new_viewer._viewer_plugins.remove(plugin) - if pyrender_viewer is not None and plugin in pyrender_viewer.plugins: - pyrender_viewer.plugins.remove(plugin) - pyrender_viewer.remove_handlers(plugin) + for plugin in [p for p in new_viewer.plugins if type(p) in reattach_types]: + new_viewer.remove_plugin(plugin) for plugin in plugins_to_reattach: new_viewer.add_plugin(plugin) diff --git a/genesis/ext/pyrender/overlay/plugin.py b/genesis/ext/pyrender/overlay/plugin.py index a0ad8ac98..410180b0b 100644 --- a/genesis/ext/pyrender/overlay/plugin.py +++ b/genesis/ext/pyrender/overlay/plugin.py @@ -91,9 +91,9 @@ def __init__( ) super().__init__() - # InteractiveScene wrapping the current scene, created and owned by this plugin in build(). It backs - # the scene-editing controls (feature gating + rebuild) so the user never instantiates one manually. - self._interactive_scene = None + # InteractiveScene wrapping the current scene, created and owned by this plugin in build(). It backs the + # scene-editing controls (feature gating + rebuild) so the user never instantiates one manually. + self.interactive_scene = None self._controlled_env_idx = controlled_env_idx self._free_joint_pos_limit = free_joint_pos_limit self._panel_width = panel_width @@ -113,8 +113,8 @@ def __init__( # Name of the tab to force-select on the next frame, then cleared. None leaves the user's selection. self._active_tab = None - # The Scene editor panel mutates this local mirror of the live entities; on "Rebuild Scene" it is - # submitted to the InteractiveScene, which applies it on the stepping thread. + # The Scene editor panel mutates this local mirror of the live entities; on "Rebuild Scene" it is submitted to + # the InteractiveScene, which applies it on the stepping thread. self._pending_dirty = False self._pending_entities_kwargs: dict[str, dict] = {} self._add_entity_file = "" @@ -135,8 +135,7 @@ def __init__( self._gizmo = None # imguizmo.im_guizmo module (lazy loaded) self._gizmo_operation = None # gizmo.OPERATION.translate self._gizmo_mode = None # gizmo.MODE.world - self._gizmo_entity_idx = -1 # which free-joint entity is selected for gizmo - self._gizmo_cached_matrix = None # cached 4x4 object matrix while dragging (avoids qpos round-trip jitter) + self._gizmo_entity_idx = -1 # which entity is selected for gizmo manipulation # Per-entity euler/quat mode: entity_idx -> "euler" or "quat" self._rotation_mode = {} # Per-entity wireframe state: entity_idx -> bool @@ -157,19 +156,18 @@ def register_panel(self, callback, section="side"): def build(self, viewer: "Viewer", camera, scene: "Scene"): """Store references; ImGui initialization is deferred to on_draw (viewer thread).""" super().build(viewer, camera, scene) - # Reset ImGui state so it re-initializes in the new viewer thread - # (needed after scene rebuild creates a new viewer/OpenGL context) - # Don't destroy the old context here, it belonged to the old viewer - # thread and is already invalid after scene.destroy(). + # Reset ImGui state so it re-initializes in the new viewer thread (needed after scene rebuild creates a new + # viewer/OpenGL context). Don't destroy the old context here, it belonged to the old viewer thread and is + # already invalid after scene.destroy(). if self._init_attempted: self._impl = None self._io = None self._available = False self._init_attempted = False self._last_time = None - # Non-batched scenes (n_envs == 0) expect envs_idx=None on entity setters and return 1D qpos - # tensors. Collapse the controlled index to None so downstream code can pass it through - # unconditionally without branching on the batched/non-batched shape. + # Non-batched scenes (n_envs == 0) expect envs_idx=None on entity setters and return 1D qpos tensors. Collapse + # the controlled index to None so downstream code can pass it through unconditionally without branching on the + # batched/non-batched shape. if scene.n_envs == 0: self._controlled_env_idx = None elif self._controlled_env_idx is not None and not (0 <= self._controlled_env_idx < scene.n_envs): @@ -179,26 +177,31 @@ def build(self, viewer: "Viewer", camera, scene: "Scene"): # Cache entity data now (doesn't require OpenGL) self._cache_entity_data() self._capture_pending_entities_kwargs() - # Wrap the scene on first build. The InteractiveScene is the controller (it owns play/pause, stepping - # and rebuild); this overlay is just a view that reads and toggles its state. On a rebuild the plugin is - # re-attached to the reconstructed scene (same object), so the existing wrapper still applies. - if self._interactive_scene is None: - self._interactive_scene = InteractiveScene(scene) + # Wrap the scene on first build. The InteractiveScene is the controller (it owns play/pause, stepping and + # rebuild); this overlay is just a view that reads and toggles its state. On a rebuild the plugin is re-attached + # to the reconstructed scene (same object), so the existing wrapper still applies. + if self.interactive_scene is None: + self.interactive_scene = InteractiveScene(scene) @property def _supported_features(self) -> frozenset[InteractiveFeature]: """Editing features advertised by the plugin's InteractiveScene for the current simulator mode, queried live. Each scene-editing control gates on its own feature and renders disabled when absent.""" - return self._interactive_scene.supported_features + return self.interactive_scene.supported_features def _refresh_visuals(self): - """Refresh render transforms after a GUI-driven mutation. Caller must hold the render lock.""" + """Refresh render transforms after a GUI-driven mutation. + + Caller must hold the render lock. Covers both the rigid and kinematic solvers, since both manage + KinematicEntity-based entities the browser can pose.""" rigid_solver = self.scene.rigid_solver - if not rigid_solver.is_active: - return - rigid_solver.update_geoms_render_T() - rigid_solver.update_vgeoms() - rigid_solver.update_vgeoms_render_T() + # Collision-geom transforms only exist on the rigid solver; visual-geom transforms apply to both. + if rigid_solver.is_active: + rigid_solver.update_geoms_render_T() + for solver in (rigid_solver, self.scene.kinematic_solver): + if solver.is_active: + solver.update_vgeoms() + solver.update_vgeoms_render_T() ctx = self.viewer.gs_context ctx.update_link_frame() ctx.update_rigid() @@ -217,7 +220,7 @@ def _apply_entity_vis_mode(self, entity, mode: str): with self.viewer.render_lock: ctx = self.viewer.gs_context - rigid_solver = self.scene.rigid_solver + solver = entity.solver old_geoms = entity.vgeoms if old_mode == "visual" else entity.geoms for geom in old_geoms: @@ -230,9 +233,7 @@ def _apply_entity_vis_mode(self, entity, mode: str): is_collision = mode == "collision" geoms, geoms_T = ( - (entity.vgeoms, rigid_solver._vgeoms_render_T) - if mode == "visual" - else (entity.geoms, rigid_solver._geoms_render_T) + (entity.vgeoms, solver._vgeoms_render_T) if mode == "visual" else (entity.geoms, solver._geoms_render_T) ) for geom in geoms: geom_envs_idx = ctx._get_geom_active_envs_idx(geom, ctx.rendered_envs_idx) @@ -273,16 +274,15 @@ def _init_imgui(self): self._impl._window = self.viewer self._io = imgui.get_io() self._io.set_ini_filename("") # Don't persist window positions - # Render the first frame as if the window is unfocused so ImGui's keyboard nav does not auto-pick - # the first focusable widget and draw a nav highlight on top of it. Pyglet's Win32 backend reports - # the window as focused at startup, which would otherwise leave the first entity header with a - # visible highlight until the user interacts. Subsequent focus events from pyglet (mouse click, - # key press, etc.) restore normal focus behavior on demand. + # Render the first frame as if the window is unfocused so ImGui's keyboard nav does not auto-pick the first + # focusable widget and draw a nav highlight on top of it. Pyglet's Win32 backend reports the window as + # focused at startup, which would otherwise leave the first entity header with a visible highlight until the + # user interacts. Subsequent focus events from pyglet (mouse click, key press, etc.) restore normal focus + # behavior on demand. self._io.add_focus_event(False) - # Set up clipboard (pyglet backend doesn't do this by default) - # Pyglet caches _clipboard_str and only clears it on SelectionClear - # events, which may not be dispatched in time. Invalidate the cache - # before each read so we always get fresh system clipboard content. + # Set up clipboard (pyglet backend doesn't do this by default). Pyglet caches _clipboard_str and only clears + # it on SelectionClear events, which may not be dispatched in time. Invalidate the cache before each read so + # we always get fresh system clipboard content. window_ref = self.viewer def _get_clipboard(_ctx): @@ -322,9 +322,14 @@ def _set_clipboard(_ctx, text): print(f"ImGuiOverlayPlugin: Failed to initialize ImGui: {e}") def _cache_entity_data(self): - """Cache static joint metadata from all rigid entities.""" + """Cache static joint metadata from all rigid and kinematic entities. + + RigidEntity derives from KinematicEntity and both expose the same joint API, so the entity browser controls + them uniformly.""" self._entity_cache.clear() - for entity in self.scene.rigid_solver.entities: + for entity in self.scene.entities: + if not isinstance(entity, gs.engine.entities.KinematicEntity): + continue if entity.n_dofs == 0: # Still include for vis_mode toggle, but no joint data self._entity_cache[entity.idx] = EntityCacheEntry( @@ -359,10 +364,13 @@ def _capture_pending_entities_kwargs(self): self._pending_entities_kwargs = {} for entity in self.scene.entities: kwargs: dict[str, Any] = {"morph": entity.morph} - if isinstance(entity, gs.engine.entities.RigidEntity): + # Carry the material and surface so a rebuild preserves the entity's solver (e.g. a Kinematic entity must + # not silently become Rigid, the add_entity default). visualize_contact is rigid-only. + if isinstance(entity, gs.engine.entities.KinematicEntity): kwargs["material"] = entity.material kwargs["surface"] = entity.surface - kwargs["visualize_contact"] = entity.visualize_contact + if isinstance(entity, gs.engine.entities.RigidEntity): + kwargs["visualize_contact"] = entity.visualize_contact self._pending_entities_kwargs[entity.name] = kwargs def _is_capturing(self) -> bool: @@ -501,7 +509,7 @@ def _render_control_panel(self): def _render_sim_controls(self): """Render simulation control buttons, time display, and FPS.""" imgui = self._imgui - interactive = self._interactive_scene + interactive = self.interactive_scene # State label if interactive.paused: @@ -509,8 +517,8 @@ def _render_sim_controls(self): else: imgui.text_colored((0.4, 0.9, 0.4, 1.0), "Running") - # Play/Pause and Reset (always visible), Step (only when paused). Auto-fit the label but with a 60-px - # floor so single-word verbs share a consistent baseline width and never get truncated. + # Play/Pause and Reset (always visible), Step (only when paused). Auto-fit the label but with a 60-px floor so + # single-word verbs share a consistent baseline width and never get truncated. play_pause = "Pause" if not interactive.paused else "Play" if imgui.button(play_pause, size=button_size_with_min(imgui, play_pause, 60.0)): interactive.resume() if interactive.paused else interactive.pause() @@ -520,10 +528,7 @@ def _render_sim_controls(self): interactive.step(self._step_count) imgui.same_line() if imgui.button("Reset", size=button_size_with_min(imgui, "Reset", 60.0)): - with self.viewer.render_lock: - self.scene.reset() - self.viewer.gs_context.clear_dynamic_nodes(only_outdated=False) - self._refresh_visuals() + interactive.reset() # Time display (frame count * dt = simulation time) sim_time = self.scene.t * self.scene.sim.dt @@ -602,54 +607,51 @@ def _render_visualization(self): self.viewer._camera_node.camera = self.viewer._default_persp_cam def _render_gizmo(self): - """Render 3D manipulation gizmo for the selected free-joint entity.""" + """Render the 3D manipulation gizmo for the selected entity, translating/rotating its base link. + + Works for fixed and floating base alike, applying ImGuizmo's resulting absolute pose via set_pos / set_quat. + The gizmo must be fed a projection with a finite far plane: with the renderer's infinite far plane ImGuizmo's + mouse-ray unprojection is ill-conditioned for an off-axis camera, quantizing the drag to a coarse grid.""" gizmo = self._gizmo Matrix16 = gizmo.Matrix16 data = self._entity_cache.get(self._gizmo_entity_idx) - if data is None or not data.joint_data.has_free_joint: + if data is None: return entity = data.entity - qs = data.joint_data.free_joint_q_start - - # While actively dragging, use the cached matrix to avoid qpos round-trip jitter. - # Only read from qpos when not dragging (to pick up external changes). - if gizmo.is_using() and self._gizmo_cached_matrix is not None: - obj_mat = self._gizmo_cached_matrix - else: - # Get current qpos - qpos = tensor_to_array(entity.get_qpos()) - if self._controlled_env_idx is not None: - qpos = qpos[self._controlled_env_idx] - # Extract position and quaternion from qpos - pos = qpos[qs : qs + 3] - quat_wxyz = qpos[qs + 3 : qs + 7] # w, x, y, z - - rot = R.from_quat([quat_wxyz[1], quat_wxyz[2], quat_wxyz[3], quat_wxyz[0]]) # scipy uses x,y,z,w - - obj_mat = np.eye(4) - obj_mat[:3, :3] = rot.as_matrix() - obj_mat[:3, 3] = pos + pos = tensor_to_array(entity.get_pos()) + quat_wxyz = tensor_to_array(entity.get_quat()) + if self._controlled_env_idx is not None: + pos = pos[self._controlled_env_idx] + quat_wxyz = quat_wxyz[self._controlled_env_idx] + rot = R.from_quat([quat_wxyz[1], quat_wxyz[2], quat_wxyz[3], quat_wxyz[0]]) # scipy uses x,y,z,w + obj_mat = np.eye(4) + obj_mat[:3, :3] = rot.as_matrix() + obj_mat[:3, 3] = pos # ImGuizmo expects column-major (transpose for row-major numpy) object_matrix = Matrix16(obj_mat.T.flatten().tolist()) - # Get view matrix (inverse of camera pose) cam_pose = self.viewer._trackball._n_pose.copy() - view_mat = np.linalg.inv(cam_pose) - camera_view = Matrix16(view_mat.T.flatten().tolist()) + camera_view = Matrix16(np.linalg.inv(cam_pose).T.flatten().tolist()) - # Get projection matrix w, h = int(self._io.display_size.x), int(self._io.display_size.y) - if w > 0 and h > 0: - proj = self.camera.camera.get_projection_matrix(width=w, height=h) - camera_proj = Matrix16(proj.T.flatten().tolist()) - else: + if w <= 0 or h <= 0: return + # A perspective camera (proj[3, 3] == 0) renders with an infinite far plane (proj[2, 2] == -1), which makes + # ImGuizmo's mouse-ray unprojection ill-conditioned for an off-axis camera and snaps the drag to a coarse grid; + # substitute a finite far plane (fov, aspect and near are preserved). An orthographic camera has parallel rays + # (no such issue) and a different matrix layout, so leave its projection untouched. + proj = self.camera.camera.get_projection_matrix(width=w, height=h).copy() + if proj[3, 3] == 0.0: + near = proj[2, 3] / (proj[2, 2] - 1.0) + far = 1000.0 + proj[2, 2] = -(far + near) / (far - near) + proj[2, 3] = -2.0 * far * near / (far - near) + camera_proj = Matrix16(proj.T.flatten().tolist()) - # Draw gizmo modified = gizmo.manipulate( camera_view, camera_proj, @@ -657,36 +659,21 @@ def _render_gizmo(self): self._gizmo_mode, object_matrix, ) + if not modified: + return - if modified: - # Extract new transform from modified matrix (column-major -> row-major) - new_mat = np.array(object_matrix.values).reshape(4, 4).T - # Cache the matrix for next frame to avoid qpos round-trip jitter - self._gizmo_cached_matrix = new_mat.copy() - - new_pos = new_mat[:3, 3] - new_rot = R.from_matrix(new_mat[:3, :3]) - new_quat_xyzw = new_rot.as_quat() # scipy: x,y,z,w - new_quat_wxyz = [new_quat_xyzw[3], new_quat_xyzw[0], new_quat_xyzw[1], new_quat_xyzw[2]] - - # Read current qpos for non-free-joint DOFs - qpos = tensor_to_array(entity.get_qpos()) - if self._controlled_env_idx is not None: - qpos = qpos[self._controlled_env_idx] - - # Update only the free-joint DOFs - new_qpos = list(qpos) - new_qpos[qs : qs + 3] = new_pos.tolist() - new_qpos[qs + 3 : qs + 7] = new_quat_wxyz - - # Auto-pause on gizmo edit - self._interactive_scene.pause() - with self.viewer.render_lock: - entity.set_qpos(new_qpos, envs_idx=self._controlled_env_idx) - self._refresh_visuals() - elif not gizmo.is_using(): - # Clear cache when drag ends so next interaction reads fresh qpos - self._gizmo_cached_matrix = None + # ImGuizmo wrote the new absolute pose into object_matrix. + new_mat = np.array(object_matrix.values).reshape(4, 4).T + self.interactive_scene.pause() + with self.viewer.render_lock: + if self._gizmo_operation == gizmo.OPERATION.rotate: + quat_xyzw = R.from_matrix(new_mat[:3, :3]).as_quat() # scipy: x,y,z,w + new_quat_wxyz = np.array([quat_xyzw[3], quat_xyzw[0], quat_xyzw[1], quat_xyzw[2]]) + # set_quat must be absolute (relative=False), since the KinematicEntity default is relative. + entity.set_quat(new_quat_wxyz, envs_idx=self._controlled_env_idx, relative=False) + else: + entity.set_pos(new_mat[:3, 3], envs_idx=self._controlled_env_idx) + self._refresh_visuals() def _is_gizmo_active(self): """Check if the gizmo is being used (for input blocking).""" @@ -967,8 +954,8 @@ def _render_scene_editor(self): self._pending_dirty = True imgui.unindent() - # Rebuild button. The InteractiveScene performs the actual rebuild on the stepping thread; doing it - # here on the viewer thread would destroy the OpenGL context we are rendering from. + # Rebuild button. The InteractiveScene performs the actual rebuild on the stepping thread; doing it here on the + # viewer thread would destroy the OpenGL context we are rendering from. if self._pending_dirty: imgui.text_colored((1.0, 0.7, 0.0, 1.0), "Changes pending") imgui.begin_disabled(rebuild_disabled) @@ -976,7 +963,7 @@ def _render_scene_editor(self): imgui.end_disabled() self._maybe_show_disabled_tooltip(rebuild_disabled) if rebuild_clicked and not rebuild_disabled: - self._interactive_scene.rebuild(entities_kwargs=self._pending_entities_kwargs) + self.interactive_scene.rebuild(entities_kwargs=self._pending_entities_kwargs) self._pending_dirty = False def _render_entity_browser(self): @@ -989,8 +976,13 @@ def _render_entity_browser(self): for entity_idx, data in self._entity_cache.items(): entity = data.entity + # Tag each entry with the entity class (e.g. , ) so the type is visible, + # matching the style used by the option reprs. Controls unavailable for kinematic entities are + # disabled rather than removed, keeping the panel layout consistent across entity types. + is_rigid = isinstance(entity, gs.engine.entities.RigidEntity) expanded = imgui.collapsing_header( - f"{data.name}##entity_{entity_idx}", flags=imgui.TreeNodeFlags_.default_open + f"{data.name} <{type(entity).__name__}>##entity_{entity_idx}", + flags=imgui.TreeNodeFlags_.default_open, ) if not expanded: continue @@ -1000,16 +992,21 @@ def _render_entity_browser(self): # DOF count display imgui.text(f"DOFs: {data.n_dofs}") - # Vis mode combo + # Vis mode combo. Kinematic entities are visual-only (no collision geoms), so the control is disabled for + # them; a disabled combo cannot change, so collision mode is never applied to a kinematic entity. vis_modes = ["visual", "collision"] current_mode = entity.surface.vis_mode current_mode_idx = vis_modes.index(current_mode) if current_mode in vis_modes else 0 + imgui.begin_disabled(not is_rigid) changed_mode, new_mode_idx = imgui.combo(f"Vis Mode##vis_{entity_idx}", current_mode_idx, vis_modes) + imgui.end_disabled() + if not is_rigid and imgui.is_item_hovered(imgui.HoveredFlags_.allow_when_disabled.value): + imgui.set_tooltip("Only available for rigid entities") if changed_mode: self._apply_entity_vis_mode(entity, vis_modes[new_mode_idx]) - # Per-entity wireframe toggle. Material lives on render primitives, so we walk the - # active geom set (vgeoms for visual mode, geoms otherwise) and flip the flag on each. + # Per-entity wireframe toggle. Material lives on render primitives, so we walk the active geom set (vgeoms + # for visual mode, geoms otherwise) and flip the flag on each. is_wireframe = self._wireframe_state.get(entity_idx, False) changed_wf, new_wf = imgui.checkbox(f"Wireframe##wf_{entity_idx}", is_wireframe) if changed_wf: @@ -1025,16 +1022,21 @@ def _render_entity_browser(self): primitive.material.wireframe = new_wf ctx._scene._meshes_updated = True - # Visualize contact toggle - show_contact = entity.visualize_contact + # Visualize contact toggle. Contacts only exist for dynamically simulated rigid entities; for kinematic + # entities the control is disabled and reads False, since they carry no visualize_contact state. + show_contact = entity.visualize_contact if is_rigid else False + imgui.begin_disabled(not is_rigid) changed_contact, new_contact = imgui.checkbox(f"Show Contacts##contact_{entity_idx}", show_contact) + imgui.end_disabled() + if not is_rigid and imgui.is_item_hovered(imgui.HoveredFlags_.allow_when_disabled.value): + imgui.set_tooltip("Only available for rigid entities") if changed_contact: entity._visualize_contact = new_contact for link in entity.links: link._visualize_contact = new_contact - # Gizmo toggle for free-joint entities - if data.joint_data.has_free_joint and self._gizmo is not None: + # Gizmo toggle to translate/rotate the entity's base link (fixed or floating base). + if self._gizmo is not None: gizmo_active = self._gizmo_entity_idx == entity_idx changed_gizmo, new_gizmo = imgui.checkbox(f"Gizmo##gizmo_{entity_idx}", gizmo_active) if changed_gizmo: @@ -1100,7 +1102,7 @@ def _render_entity_browser(self): if changed_any: # Auto-pause when user edits joints - self._interactive_scene.pause() + self.interactive_scene.pause() if not (data.joint_data.has_free_joint and self._rotation_mode.get(entity_idx) == "euler"): # Normalize any edited quaternion groups (quat mode only) for qstart, qend in data.joint_data.quat_groups: @@ -1150,7 +1152,7 @@ def _render_joints_euler_mode(self, entity, data, entity_idx, qpos, new_qpos): ) if changed_pos or changed_rot: - self._interactive_scene.pause() + self.interactive_scene.pause() new_dofs = list(dofs) if changed_pos: new_dofs[0], new_dofs[1], new_dofs[2] = new_pos @@ -1198,8 +1200,8 @@ def on_close(self) -> None: and scene teardown, so guard against a second call once the context is already destroyed.""" if self._ctx is None: return - # Make our context current before tearing it down; the backend shutdown and destroy_context both - # operate on the current ImGui context. + # Make our context current before tearing it down; the backend shutdown and destroy_context both operate on the + # current ImGui context. self._imgui.set_current_context(self._ctx) if self._available and self._impl is not None: self._impl.shutdown() diff --git a/genesis/ext/pyrender/viewer.py b/genesis/ext/pyrender/viewer.py index 2963a2ee2..9f66e1031 100644 --- a/genesis/ext/pyrender/viewer.py +++ b/genesis/ext/pyrender/viewer.py @@ -1323,8 +1323,10 @@ def refresh(self): self._offscreen_event.clear() self.switch_to() - pyglet.clock.tick() + # Dispatch input events before drawing, so the frame (and the ImGui overlay / gizmo it renders) reacts to the + # current mouse and keyboard state. Drawing first and dispatching afterwards leaves interactive controls one + # frame behind the cursor, which makes dragging the gizmo feel stuttery. if sys.platform == "win32": # even changing `platform_event_loop.step(0.0)` to 0.001 causes the viewer to hang on Windows # this is a workaround on Windows. not sure if it's correct @@ -1335,6 +1337,9 @@ def refresh(self): self.dispatch_pending_events() if self._is_active: self.dispatch_events() + + pyglet.clock.tick() + if self._is_active: self.flip() diff --git a/genesis/vis/rasterizer_context.py b/genesis/vis/rasterizer_context.py index ca0cf2ac1..bc6aee593 100644 --- a/genesis/vis/rasterizer_context.py +++ b/genesis/vis/rasterizer_context.py @@ -306,19 +306,20 @@ def off_world_frame(self): self.world_frame_node = None self.world_frame_shown = False + def _link_frame_T(self, solver): + """World-space 4x4 transforms for every (env, link) of solver, flattened in env-major, link-minor order.""" + pos = qd_to_numpy(solver.links_state.pos, self.rendered_envs_idx, transpose=True, copy=True) + quat = qd_to_numpy(solver.links_state.quat, self.rendered_envs_idx, transpose=True) + pos += self.scene.envs_offset[self.rendered_envs_idx, None] + return gu.trans_quat_to_T(pos.reshape(-1, 3), quat.reshape(-1, 4)) + def on_link_frame(self): if not self.link_frame_shown: - if self.sim.rigid_solver.is_active: - pos = qd_to_numpy( - self.sim.rigid_solver.links_state.pos, self.rendered_envs_idx, transpose=True, copy=True - ) - quat = qd_to_numpy(self.sim.rigid_solver.links_state.quat, self.rendered_envs_idx, transpose=True) - pos += self.scene.envs_offset[self.rendered_envs_idx, None] - all_T = gu.trans_quat_to_T(pos.reshape(-1, 3), quat.reshape(-1, 4)) - - if self.env_separate_rigid: - n_links = len(self.sim.rigid_solver.links) - for i, link in enumerate(self.sim.rigid_solver.links): + if self.env_separate_rigid: + for solver in self._rigid_solvers(): + all_T = self._link_frame_T(solver) + n_links = len(solver.links) + for i, link in enumerate(solver.links): mesh = pyrender.Mesh.from_trimesh( mesh=self.link_frame_mesh, poses=all_T[i::n_links], @@ -326,10 +327,12 @@ def on_link_frame(self): is_marker=True, ) self.link_frame_nodes[link.uid] = self.add_node(mesh) - else: + else: + all_T_parts = [self._link_frame_T(solver) for solver in self._rigid_solvers()] + if all_T_parts: mesh = pyrender.Mesh.from_trimesh( mesh=self.link_frame_mesh, - poses=all_T, + poses=np.concatenate(all_T_parts, axis=0), is_marker=True, ) self.link_frame_node = self.add_node(mesh) @@ -341,35 +344,30 @@ def off_link_frame(self): for node in self.link_frame_nodes.values(): self.remove_node(node) self.link_frame_nodes.clear() - else: + elif self.link_frame_node is not None: self.remove_node(self.link_frame_node) self.link_frame_node = None self.link_frame_shown = False def update_link_frame(self): if self.link_frame_shown: - if self.sim.rigid_solver.is_active: - pos = qd_to_numpy( - self.sim.rigid_solver.links_state.pos, self.rendered_envs_idx, transpose=True, copy=True - ) - quat = qd_to_numpy(self.sim.rigid_solver.links_state.quat, self.rendered_envs_idx, transpose=True) - pos += self.scene.envs_offset[self.rendered_envs_idx, None] - all_T = gu.trans_quat_to_T(pos.reshape(-1, 3), quat.reshape(-1, 4)) - - if self.env_separate_rigid: - n_links = len(self.sim.rigid_solver.links) - for i, link in enumerate(self.sim.rigid_solver.links): + if self.env_separate_rigid: + for solver in self._rigid_solvers(): + all_T = self._link_frame_T(solver) + n_links = len(solver.links) + for i, link in enumerate(solver.links): link_T = all_T[i::n_links] node = self.link_frame_nodes[link.uid] node.mesh.primitives[0].poses = link_T buf_id = self._scene.get_buffer_id(node, "model") if buf_id >= 0: self.jit.update_buffer(buf_id, link_T.transpose((0, 2, 1))) - else: - self.link_frame_node.mesh.primitives[0].poses = all_T - buf_id = self._scene.get_buffer_id(self.link_frame_node, "model") - if buf_id >= 0: - self.jit.update_buffer(buf_id, all_T.transpose((0, 2, 1))) + elif self.link_frame_node is not None: + all_T = np.concatenate([self._link_frame_T(solver) for solver in self._rigid_solvers()], axis=0) + self.link_frame_node.mesh.primitives[0].poses = all_T + buf_id = self._scene.get_buffer_id(self.link_frame_node, "model") + if buf_id >= 0: + self.jit.update_buffer(buf_id, all_T.transpose((0, 2, 1))) def on_tool(self): if self.sim.tool_solver.is_active: diff --git a/genesis/vis/viewer.py b/genesis/vis/viewer.py index 7b7e12861..3614571ef 100644 --- a/genesis/vis/viewer.py +++ b/genesis/vis/viewer.py @@ -48,11 +48,11 @@ def __init__(self, options: "ViewerOptions", context): self._camera_fov = options.camera_fov self._enable_help_text = options.enable_help_text - self._viewer_plugins: list["ViewerPlugin"] = [] + self._plugins: list["ViewerPlugin"] = [] if options.enable_default_keybinds: - self._viewer_plugins.append(DefaultControlsPlugin()) + self._plugins.append(DefaultControlsPlugin()) if options.enable_gui: - self._viewer_plugins.append(ImGuiOverlayPlugin()) + self._plugins.append(ImGuiOverlayPlugin()) # Validate viewer options if any(e.shape != (3,) for e in (self._camera_init_pos, self._camera_init_lookat, self._camera_up)): @@ -80,7 +80,7 @@ def build(self, scene): # would close and reopen the OS window). The preserved pyrender viewer is re-pointed at the rebuilt # scene graph in place. if self._pyrender_viewer is not None: - self._pyrender_viewer.rebind(self.context, self._viewer_plugins) + self._pyrender_viewer.rebind(self.context, self._plugins) self.lock = ViewerLock(self._pyrender_viewer) self._is_built = True return @@ -118,7 +118,7 @@ def build(self, scene): plane_reflection=self.context.plane_reflection, env_separate_rigid=self.context.env_separate_rigid, enable_help_text=self._enable_help_text, - plugins=self._viewer_plugins, + plugins=self._plugins, viewer_flags={ "window_title": f"Genesis {gs.__version__}", "refresh_rate": self._refresh_rate, @@ -375,15 +375,35 @@ def add_plugin(self, plugin: "ViewerPlugin") -> "ViewerPlugin": plugin : ViewerPlugin The viewer plugin to add. """ - self._viewer_plugins.append(plugin) + self._plugins.append(plugin) if self.is_built: self._pyrender_viewer.register_plugin(plugin) return plugin + def remove_plugin(self, plugin: "ViewerPlugin") -> None: + """ + Remove a viewer plugin from the viewer, detaching it from the live render loop if already built. + + Parameters + ---------- + plugin : ViewerPlugin + The viewer plugin to remove. + """ + if plugin in self._plugins: + self._plugins.remove(plugin) + if self.is_built and plugin in self._pyrender_viewer.plugins: + self._pyrender_viewer.plugins.remove(plugin) + self._pyrender_viewer.remove_handlers(plugin) + # ------------------------------------------------------------------------------------ # ----------------------------------- properties ------------------------------------- # ------------------------------------------------------------------------------------ + @property + def plugins(self): + """The registered viewer plugins, read-only; use ``add_plugin`` to register one.""" + return tuple(self._plugins) + @property def is_built(self): return self._is_built diff --git a/tests/test_imgui_overlay.py b/tests/test_imgui_overlay.py index 287339726..b8263655f 100644 --- a/tests/test_imgui_overlay.py +++ b/tests/test_imgui_overlay.py @@ -174,7 +174,7 @@ def test_editing_controls(png_snapshot, monkeypatch): _apply_deterministic_imgui_overrides(monkeypatch) - plugin = next(p for p in scene.viewer._viewer_plugins if isinstance(p, ImGuiOverlayPlugin)) + plugin = next(p for p in scene.viewer.plugins if isinstance(p, ImGuiOverlayPlugin)) plugin._panel_width = 420 plugin._active_tab = "Scene" @@ -206,8 +206,8 @@ def test_scene_rebuild(): scene.build() scene_id = id(scene) - plugin = next(p for p in scene.viewer._viewer_plugins if isinstance(p, ImGuiOverlayPlugin)) - interactive = plugin._interactive_scene + plugin = next(p for p in scene.viewer.plugins if isinstance(p, ImGuiOverlayPlugin)) + interactive = plugin.interactive_scene assert interactive is not None names_before = [entity.name for entity in scene.entities] # The rebuild must reuse the live window rather than closing and reopening it. diff --git a/tests/test_viewer.py b/tests/test_viewer.py index 3bc7edc1f..b7af11f7e 100644 --- a/tests/test_viewer.py +++ b/tests/test_viewer.py @@ -341,9 +341,7 @@ def check_event_count(): # Confirm the raycaster picked the expected env if target_env_idx is not None: - plugin = next( - p for p in scene.viewer._viewer_plugins if isinstance(p, gs.vis.viewer_plugins.MouseInteractionPlugin) - ) + plugin = next(p for p in scene.viewer.plugins if isinstance(p, gs.vis.viewer_plugins.MouseInteractionPlugin)) assert plugin._interact_env_idx == target_env_idx, ( f"Expected mouse to pick env {target_env_idx}, got env {plugin._interact_env_idx}" ) diff --git a/tests/utils.py b/tests/utils.py index 0a7ef24b2..44364ab16 100644 --- a/tests/utils.py +++ b/tests/utils.py @@ -38,7 +38,7 @@ DEFAULT_BRANCH_NAME = "main" HUGGINGFACE_ASSETS_REVISION = "8ae68c5236abf310367345dfb6dd6e6e8affe3c6" -HUGGINGFACE_SNAPSHOT_REVISION = "182661c4a96a857e96bbbc184c93ed091f4950a7" +HUGGINGFACE_SNAPSHOT_REVISION = "1e3c68ff4a8acc820ed3e6d255b044cf707aa324" MESH_EXTENSIONS = (".mtl", *MESH_FORMATS, *GLTF_FORMATS, *USD_FORMATS) IMAGE_EXTENSIONS = (".png", ".jpg")