diff --git a/.github/workflows/generic.yml b/.github/workflows/generic.yml index 4be0cc2ba8..1e1aabe349 100644 --- a/.github/workflows/generic.yml +++ b/.github/workflows/generic.yml @@ -16,7 +16,7 @@ jobs: matrix: # See official Github documentation for details: https://shorturl.at/NJgsj OS: ["ubuntu-22.04", "ubuntu-24.04", "macos-15", "windows-cpu-4-core"] - PYTHON_VERSION: ["3.10", "3.11", "3.12"] + PYTHON_VERSION: ["3.10", "3.11", "3.12", "3.13"] env: HF_HUB_DOWNLOAD_TIMEOUT: 60 @@ -103,7 +103,7 @@ jobs: - name: Install Genesis run: | - pip install -e '.[dev,render]' + pip install -e '.[dev]' - name: Run unit tests run: | diff --git a/.github/workflows/production.yml b/.github/workflows/production.yml index e3825c3909..7daf97463d 100644 --- a/.github/workflows/production.yml +++ b/.github/workflows/production.yml @@ -22,7 +22,7 @@ jobs: WANDB_API_KEY: ${{ secrets.WANDB_API_KEY }} HF_TOKEN: ${{ secrets.HF_TOKEN }} HF_HUB_DOWNLOAD_TIMEOUT: 60 - GENESIS_IMAGE_VER: "1_0" + GENESIS_IMAGE_VER: "1_1" TIMEOUT_MINUTES: 180 steps: diff --git a/README.md b/README.md index d9cadadbe1..a95b77c02b 100644 --- a/README.md +++ b/README.md @@ -77,7 +77,7 @@ Install **PyTorch** first following the [official instructions](https://pytorch. Then, install Genesis via PyPI: ```bash -pip install genesis-world # Requires Python>=3.10,<3.13; +pip install genesis-world # Requires Python>=3.10,<3.14; ``` For the latest version to date, make sure that `pip` is up-to-date via `pip install --upgrade pip`, then run command: @@ -172,6 +172,7 @@ Genesis's development has been made possible thanks to these open-source project - [libccd](https://github.com/danfis/libccd): Reference for collision detection. - [PyRender](https://github.com/mmatl/pyrender): Rasterization-based renderer. - [LuisaCompute](https://github.com/LuisaGroup/LuisaCompute) and [LuisaRender](https://github.com/LuisaGroup/LuisaRender): Ray-tracing DSL. +- [Madrona](https://github.com/shacklettbp/madrona) and [Madrona-mjx](https://github.com/shacklettbp/madrona_mjx): Batch renderer backend ## Associated Papers diff --git a/README_FR.md b/README_FR.md index 7fdf053c79..8506ac85b0 100644 --- a/README_FR.md +++ b/README_FR.md @@ -69,7 +69,7 @@ Page du projet : Genesis est disponible via PyPI : ```bash -pip install genesis-world # Nécessite Python>=3.10,<3.13; +pip install genesis-world # Nécessite Python>=3.10,<3.14; ``` Vous devez également installer **PyTorch** en suivant [les instructions officielles](https://pytorch.org/get-started/locally/). diff --git a/README_JA.md b/README_JA.md index 5a9e9c5fff..af4cf28ab3 100644 --- a/README_JA.md +++ b/README_JA.md @@ -69,7 +69,7 @@ Genesisの目指すところ: GenesisはPyPIで利用可能です: ```bash -pip install genesis-world # Python>=3.10,<3.13 が必要です; +pip install genesis-world # Python>=3.10,<3.14 が必要です; ``` また、**PyTorch**を[公式手順](https://pytorch.org/get-started/locally/)に従ってインストールする必要があります。 diff --git a/README_KR.md b/README_KR.md index 4c3f537e24..6bb2a7d684 100644 --- a/README_KR.md +++ b/README_KR.md @@ -69,7 +69,7 @@ Genesis의 목표: Genesis는 PyPI를 통해 설치할 수 있습니다: ```bash -pip install genesis-world # Python>=3.10,<3.13 필요 +pip install genesis-world # Python>=3.10,<3.14 필요 ``` 또한, [공식 설명서](https://pytorch.org/get-started/locally/)에 따라 **PyTorch**를 설치해야 합니다. diff --git a/examples/drone/interactive_drone.py b/examples/drone/interactive_drone.py index 781d9ca87a..32e5f1ea58 100644 --- a/examples/drone/interactive_drone.py +++ b/examples/drone/interactive_drone.py @@ -1,16 +1,17 @@ -import argparse -import numpy as np -import genesis as gs import time import threading + from pynput import keyboard +import numpy as np + +import genesis as gs class DroneController: def __init__(self): - self.thrust = 14468.429183500699 # Base hover RPM - constant hover - self.rotation_delta = 200 # Differential RPM for rotation - self.thrust_delta = 10 # Amount to change thrust by when accelerating/decelerating + self.thrust = 14475.8 # Base hover RPM - constant hover + self.rotation_delta = 200.0 # Differential RPM for rotation + self.thrust_delta = 10.0 # Amount to change thrust by when accelerating/decelerating self.running = True self.rpms = [self.thrust] * 4 self.pressed_keys = set() @@ -93,46 +94,37 @@ def update_thrust(self): def run_sim(scene, drone, controller): while controller.running: - try: - # Update drone with current RPMs - rpms = controller.update_thrust() - drone.set_propellels_rpm(rpms) + # Update drone with current RPMs + rpms = controller.update_thrust() + drone.set_propellels_rpm(rpms) - # Update physics - scene.step() + # Update physics + scene.step(refresh_visualizer=False) - time.sleep(1 / 60) # Limit simulation rate - except Exception as e: - print(f"Error in simulation loop: {e}") - - if scene.viewer: - scene.viewer.stop() + # Limit simulation rate + time.sleep(1.0 / scene.viewer.max_FPS) def main(): - parser = argparse.ArgumentParser() - parser.add_argument("-v", "--vis", action="store_true", default=True, help="Enable visualization (default: True)") - parser.add_argument("-m", "--mac", action="store_true", default=False, help="Running on MacOS (default: False)") - args = parser.parse_args() - # Initialize Genesis gs.init(backend=gs.cpu) - # Create scene with initial camera view - viewer_options = gs.options.ViewerOptions( - camera_pos=(0.0, -4.0, 2.0), # Now behind the drone (negative Y) - camera_lookat=(0.0, 0.0, 0.5), - camera_fov=45, - max_FPS=60, - ) - + # Create scene scene = gs.Scene( sim_options=gs.options.SimOptions( dt=0.01, gravity=(0, 0, -9.81), ), - viewer_options=viewer_options, - show_viewer=args.vis, + viewer_options=gs.options.ViewerOptions( + camera_pos=(0.0, -2.0, 1.0), + camera_lookat=(0.0, 0.0, 0.3), + camera_fov=45, + max_FPS=60, + ), + vis_options=gs.options.VisOptions( + show_world_frame=False, + ), + show_viewer=True, ) # Add entities @@ -146,38 +138,32 @@ def main(): scene.viewer.follow_entity(drone) - # Build scene - scene.build() - # Initialize controller controller = DroneController() + # Start keyboard listener. + # Note that instantiating the listener after building the scene causes segfault on MacOS. + listener = keyboard.Listener(on_press=controller.on_press, on_release=controller.on_release) + listener.start() + + # Build scene + scene.build() + # Print control instructions print("\nDrone Controls:") print("↑ - Move Forward (North)") print("↓ - Move Backward (South)") print("← - Move Left (West)") print("→ - Move Right (East)") + print("space - Increase RPM") + print("shift - Decrease RPM") print("ESC - Quit\n") print("Initial hover RPM:", controller.thrust) - # Start keyboard listener - listener = keyboard.Listener(on_press=controller.on_press, on_release=controller.on_release) - listener.start() - - if args.mac: - # Run simulation in another thread - sim_thread = threading.Thread(target=run_sim, args=(scene, drone, controller)) - sim_thread.start() - - if args.vis: - scene.viewer.start() + # Run simulation in another thread + threading.Thread(target=run_sim, args=(scene, drone, controller)).start() + scene.viewer.run() - # Wait for threads to finish - sim_thread.join() - else: - # Run simulation in main thread - run_sim(scene, drone, controller) listener.stop() diff --git a/examples/rigid/single_franka_batch_render.py b/examples/rigid/single_franka_batch_render.py new file mode 100644 index 0000000000..f962c1d5f2 --- /dev/null +++ b/examples/rigid/single_franka_batch_render.py @@ -0,0 +1,89 @@ +import argparse +import numpy as np + +import genesis as gs +from genesis.utils.geom import trans_to_T +from genesis.utils.image_exporter import FrameImageExporter + + +def main(): + parser = argparse.ArgumentParser() + parser.add_argument("-v", "--vis", action="store_true", default=False) + parser.add_argument("-c", "--cpu", action="store_true", default=False) + parser.add_argument("-b", "--n_envs", type=int, default=3) + parser.add_argument("-s", "--n_steps", type=int, default=2) + parser.add_argument("-r", "--render_all_cameras", action="store_true", default=False) + parser.add_argument("-o", "--output_dir", type=str, default="img_output/test") + parser.add_argument("-u", "--use_rasterizer", action="store_true", default=False) + args = parser.parse_args() + + ########################## init ########################## + gs.init(backend=gs.cpu if args.cpu else gs.gpu) + + ########################## create a scene ########################## + scene = gs.Scene( + renderer=gs.options.renderers.BatchRenderer( + use_rasterizer=args.use_rasterizer, + ), + ) + + ########################## entities ########################## + plane = scene.add_entity( + gs.morphs.Plane(), + ) + franka = scene.add_entity( + gs.morphs.MJCF(file="xml/franka_emika_panda/panda.xml"), + visualize_contact=True, + ) + + ########################## cameras ########################## + cam_0 = scene.add_camera( + res=(512, 512), + pos=(1.5, 0.5, 1.5), + lookat=(0.0, 0.0, 0.5), + fov=45, + GUI=args.vis, + ) + cam_0.attach(franka.links[6], trans_to_T(np.array([0.0, 0.5, 0.0]))) + cam_1 = scene.add_camera( + res=(512, 512), + pos=(1.5, -0.5, 1.5), + lookat=(0.0, 0.0, 0.5), + fov=45, + GUI=args.vis, + ) + scene.add_light( + pos=[0.0, 0.0, 1.5], + dir=[1.0, 1.0, -2.0], + directional=1, + castshadow=1, + cutoff=45.0, + intensity=0.5, + ) + scene.add_light( + pos=[4, -4, 4], + dir=[-1, 1, -1], + directional=0, + castshadow=1, + cutoff=45.0, + intensity=0.5, + ) + + ########################## build ########################## + scene.build(n_envs=args.n_envs) + + # Create an image exporter + exporter = FrameImageExporter(args.output_dir) + + for i in range(args.n_steps): + scene.step() + if args.render_all_cameras: + rgba, depth, _, _ = scene.render_all_cameras(rgb=True, depth=True) + exporter.export_frame_all_cameras(i, rgb=rgba, depth=depth) + else: + rgba, depth, _, _ = cam_1.render(rgb=True, depth=True) + exporter.export_frame_single_camera(i, cam_1.idx, rgb=rgba, depth=depth) + + +if __name__ == "__main__": + main() diff --git a/genesis/engine/entities/rigid_entity/rigid_geom.py b/genesis/engine/entities/rigid_entity/rigid_geom.py index be97c6febd..df471c07c9 100644 --- a/genesis/engine/entities/rigid_entity/rigid_geom.py +++ b/genesis/engine/entities/rigid_entity/rigid_geom.py @@ -874,6 +874,7 @@ def __init__( self._uvs = vmesh.uvs self._surface = vmesh.surface self._metadata = vmesh.metadata + self._color = vmesh._color def _build(self): pass diff --git a/genesis/engine/entities/rigid_entity/rigid_link.py b/genesis/engine/entities/rigid_entity/rigid_link.py index d9d8542831..4f4deb7124 100644 --- a/genesis/engine/entities/rigid_entity/rigid_link.py +++ b/genesis/engine/entities/rigid_entity/rigid_link.py @@ -1,9 +1,9 @@ from typing import TYPE_CHECKING import numpy as np -from numpy.typing import ArrayLike import taichi as ti import torch +from numpy.typing import ArrayLike import genesis as gs import trimesh diff --git a/genesis/engine/mesh.py b/genesis/engine/mesh.py index 56eef532b7..14803e1a3b 100644 --- a/genesis/engine/mesh.py +++ b/genesis/engine/mesh.py @@ -60,6 +60,7 @@ def __init__( self._surface = surface self._uvs = uvs self._metadata = metadata or {} + self._color = np.array([1.0, 1.0, 1.0, 1.0], dtype=gs.np_float) if self._surface.requires_uv(): # check uvs here if self._uvs is None: @@ -383,6 +384,7 @@ def set_color(self, color): """ Set the mesh's color. """ + self._color = color color_texture = gs.textures.ColorTexture(color=tuple(color)) opacity_texture = color_texture.check_dim(3) self._surface.update_texture(color_texture=color_texture, opacity_texture=opacity_texture, force=True) diff --git a/genesis/engine/scene.py b/genesis/engine/scene.py index c9eca095e0..427d546b26 100644 --- a/genesis/engine/scene.py +++ b/genesis/engine/scene.py @@ -1,10 +1,11 @@ import os +import pickle +import time import numpy as np import torch -import pickle -import time import taichi as ti +from numpy.typing import ArrayLike import genesis as gs import genesis.utils.geom as gu @@ -33,7 +34,7 @@ ) from genesis.options.morphs import Morph from genesis.options.surfaces import Surface -from genesis.options.renderers import Rasterizer, Renderer +from genesis.options.renderers import Rasterizer, RendererOptions from genesis.repr_base import RBC from genesis.utils.tools import FPSTracker from genesis.utils.misc import redirect_libc_stderr, tensor_to_array @@ -73,8 +74,8 @@ class Scene(RBC): The options configuring the visualization system (``scene.visualizer``). Visualizer controls both the interactive viewer and the cameras. viewer_options : gs.options.ViewerOptions The options configuring the viewer (``scene.visualizer.viewer``). - renderer : gs.renderers.Renderer - The renderer used by `camera` for rendering images. This doesn't affect the behavior of the interactive viewer. + renderer : gs.renderers.RendererOptions + The renderer options used by `camera` for rendering images. This doesn't affect the behavior of the interactive viewer. show_viewer : bool Whether to show the interactive viewer. Set it to False if you only need headless rendering. show_FPS : bool @@ -96,7 +97,7 @@ def __init__( vis_options: VisOptions | None = None, viewer_options: ViewerOptions | None = None, profiling_options: ProfilingOptions | None = None, - renderer: Renderer | None = None, + renderer: RendererOptions | None = None, show_viewer: bool | None = None, show_FPS: bool | None = None, # deprecated, use profiling_options.show_FPS instead ): @@ -152,6 +153,7 @@ def __init__( self.vis_options = vis_options self.viewer_options = viewer_options + self.renderer_options = renderer # merge options self.tool_options.copy_attributes_from(self.sim_options) @@ -184,7 +186,7 @@ def __init__( show_viewer=show_viewer, vis_options=vis_options, viewer_options=viewer_options, - renderer=renderer, + renderer_options=renderer, ) # emitters @@ -214,7 +216,7 @@ def _validate_options( vis_options: VisOptions, viewer_options: ViewerOptions, profiling_options: ProfilingOptions, - renderer: Renderer, + renderer_options: RendererOptions, ): if not isinstance(sim_options, SimOptions): gs.raise_exception("`sim_options` should be an instance of `SimOptions`.") @@ -255,7 +257,7 @@ def _validate_options( if not isinstance(profiling_options, ProfilingOptions): gs.raise_exception("`profiling_options` should be an instance of `ProfilingOptions`.") - if not isinstance(renderer, Renderer): + if not isinstance(renderer_options, RendererOptions): gs.raise_exception("`renderer` should be an instance of `gs.renderers.Renderer`.") @gs.assert_unbuilt @@ -433,7 +435,8 @@ def link_entities( if child_link._parent_idx != -1: gs.logger.warning( - "Child entity already has a parent link. This may cause the entity to break into parts. Make sure this operation is intended." + "Child entity already has a parent link. This may cause the entity to break into parts. Make sure " + "this operation is intended." ) child_link._parent_idx = parent_link.idx parent_link._child_idxs.append(child_link.idx) @@ -441,42 +444,75 @@ def link_entities( @gs.assert_unbuilt def add_light( self, - morph: Morph, - color=(1.0, 1.0, 1.0, 1.0), - intensity=20.0, - revert_dir=False, - double_sided=False, - beam_angle=180.0, + *, + morph: Morph | None = None, + color: ArrayLike | None = (1.0, 1.0, 1.0, 1.0), + intensity: float = 20.0, + revert_dir: bool | None = False, + double_sided: bool | None = False, + beam_angle: float | None = 180.0, + pos: ArrayLike | None = None, + dir: ArrayLike | None = None, + directional: bool | None = None, + castshadow: bool | None = None, + cutoff: float | None = None, ): """ - Add a light to the scene. Note that lights added this way can be instantiated from morphs (supporting `gs.morphs.Primitive` or `gs.morphs.Mesh`), and will only be used by the RayTracer renderer. + Add a light to the scene. + + Warning + ------- + The signature of this method is different depending on the renderer being used, i.e.: + - RayTracer: 'add_light(self, morph, color, intensity, revert_dir, double_sided, beam_angle)' + - BatchRender: 'add_ligth(self, pos, dir, intensity, directional, castshadow, cutoff)' + - Rasterizer: **Unsupported** Parameters ---------- morph : gs.morphs.Morph - The morph of the light. Must be an instance of `gs.morphs.Primitive` or `gs.morphs.Mesh`. + The morph of the light. Must be an instance of `gs.morphs.Primitive` or `gs.morphs.Mesh`. Only supported by + RayTracer. color : tuple of float, shape (3,) - The color of the light, specified as (r, g, b). + The color of the light, specified as (r, g, b). Only supported by RayTracer. intensity : float The intensity of the light. revert_dir : bool Whether to revert the direction of the light. If True, the light will be emitted towards the mesh's inside. + Only supported by RayTracer. double_sided : bool - Whether to emit light from both sides of surface. + Whether to emit light from both sides of surface. Only supported by RayTracer. beam_angle : float - The beam angle of the light. + The beam angle of the light. Only supported by RayTracer. + pos : tuple of float, shape (3,) + The position of the light, specified as (x, y, z). Only supported by BatchRenderer. + dir : tuple of float, shape (3,) + The direction of the light, specified as (x, y, z). Only supported by BatchRenderer. + intensity : float + The intensity of the light. Only supported by BatchRenderer. + directional : bool + Whether the light is directional. Only supported by BatchRenderer. + castshadow : bool + Whether the light casts shadows. Only supported by BatchRenderer. + cutoff : float + The cutoff angle of the light in degrees. Only supported by BatchRenderer. """ - if self.visualizer.raytracer is None: - gs.logger.warning("Light is only supported by RayTracer renderer.") - return - - if not isinstance(morph, (gs.morphs.Primitive, gs.morphs.Mesh)): - gs.raise_exception("Light morph only supports `gs.morphs.Primitive` or `gs.morphs.Mesh`.") - - mesh = gs.Mesh.from_morph_surface(morph, gs.surfaces.Plastic(smooth=False)) - self.visualizer.raytracer.add_mesh_light( - mesh, color, intensity, morph.pos, morph.quat, revert_dir, double_sided, beam_angle - ) + if self._visualizer.batch_renderer is not None: + if any(map(lambda e: e is None, (pos, dir, intensity, directional, castshadow, cutoff))): + gs.raise_exception("Input arguments do not complain with expected signature when using 'BatchRenderer'") + + self.visualizer.add_light(pos, dir, intensity, directional, castshadow, cutoff) + elif self.visualizer.raytracer is not None: + if any(map(lambda e: e is None, (morph, color, intensity, revert_dir, double_sided, beam_angle))): + gs.raise_exception("Input arguments do not complain with expected signature when using 'RayTracer'") + if not isinstance(morph, (gs.morphs.Primitive, gs.morphs.Mesh)): + gs.raise_exception("Light morph only supports `gs.morphs.Primitive` or `gs.morphs.Mesh`.") + + mesh = gs.Mesh.from_morph_surface(morph, gs.surfaces.Plastic(smooth=False)) + self.visualizer.raytracer.add_mesh_light( + mesh, color, intensity, morph.pos, morph.quat, revert_dir, double_sided, beam_angle + ) + else: + gs.raise_exception("Adding lights is only supported by 'RayTracer' and 'BatchRenderer'.") @gs.assert_unbuilt def add_camera( @@ -734,7 +770,8 @@ def _reset(self, state: SimState | None = None, *, envs_idx=None): self._forward_ready = True self._reset_grad() - # TODO: sets _t = -1; not sure this is env isolation safe + # Clear the entire cache of the visualizer. + # TODO: Could be optimized to only clear cache associated the the environments being reset. self._visualizer.reset() # TODO: sets _next_particle = 0; not sure this is env isolation safe @@ -1014,7 +1051,8 @@ def draw_debug_path(self, qposs, entity, link_idx=-1, density=0.3, frame_scaling density : float, optional Controls the sampling density of the trajectory points to visualize. Default is 0.3. frame_scaling : float, optional - Scaling factor for the visualization frames' size. Affects the length and thickness of the debug frames. Default is 1.0. + Scaling factor for the visualization frames' size. Affects the length and thickness of the debug frames. + Default is 1.0. Returns ------- @@ -1024,7 +1062,8 @@ def draw_debug_path(self, qposs, entity, link_idx=-1, density=0.3, frame_scaling Notes ----- The function uses forward kinematics (FK) to convert joint positions to Cartesian space and render debug frames. - The density parameter reduces FK computational load by sampling fewer points, with 1.0 representing the whole trajectory. + The density parameter reduces FK computational load by sampling fewer points, with 1.0 representing the whole + trajectory. """ with self._visualizer.viewer_lock: N = len(qposs) @@ -1041,6 +1080,34 @@ def draw_debug_path(self, qposs, entity, link_idx=-1, density=0.3, frame_scaling Ts, axis_length=frame_scaling * 0.1, origin_size=0.001, axis_radius=frame_scaling * 0.005 ) + @gs.assert_built + def render_all_cameras(self, rgb=True, depth=False, normal=False, segmentation=False, force_render=False): + """ + Render the scene for all cameras using the batch renderer. + + Parameters + ---------- + rgb : bool, optional + Whether to render the rgb image. + depth : bool, optional + Whether to render the depth image. + normal : bool, optional + Whether to render the normal image. + segmentation : bool, optional + Whether to render the segmentation image. + force_render : bool, optional + Whether to force render the scene. + + Returns: + A tuple of tensors of shape (n_envs, H, W, 3) if rgb is not None, + otherwise a list of tensors of shape (n_envs, H, W, 1) if depth is not None. + If n_envs == 0, the first dimension of the tensor is squeezed. + """ + if self._visualizer.batch_renderer is None: + gs.raise_exception("Method only supported by 'BatchRenderer'") + + return self._visualizer.batch_renderer.render(rgb, depth, normal, segmentation, force_render) + @gs.assert_built def clear_debug_object(self, object): """ diff --git a/genesis/engine/solvers/avatar_solver.py b/genesis/engine/solvers/avatar_solver.py index be900becc3..b926805417 100644 --- a/genesis/engine/solvers/avatar_solver.py +++ b/genesis/engine/solvers/avatar_solver.py @@ -57,7 +57,9 @@ def _kernel_step(self): @ti.kernel def _kernel_forward_kinematics_links_geoms(self, envs_idx: ti.types.ndarray()): - for i_b in envs_idx: + for i_b_ in range(envs_idx.shape[0]): + i_b = envs_idx[i_b_] + self._func_forward_kinematics( i_b, self.links_state, diff --git a/genesis/engine/solvers/rigid/rigid_solver_decomp.py b/genesis/engine/solvers/rigid/rigid_solver_decomp.py index 3f8c191080..90e2f0ba38 100644 --- a/genesis/engine/solvers/rigid/rigid_solver_decomp.py +++ b/genesis/engine/solvers/rigid/rigid_solver_decomp.py @@ -775,6 +775,7 @@ def _init_vgeom_fields(self): vgeoms_vface_start=np.array([vgeom.vface_start for vgeom in vgeoms], dtype=gs.np_int), vgeoms_vvert_end=np.array([vgeom.vvert_end for vgeom in vgeoms], dtype=gs.np_int), vgeoms_vface_end=np.array([vgeom.vface_end for vgeom in vgeoms], dtype=gs.np_int), + vgeoms_color=np.array([vgeom._color for vgeom in vgeoms], dtype=gs.np_float), # taichi variables vgeoms_info=self.vgeoms_info, static_rigid_sim_config=self._static_rigid_sim_config, @@ -2880,6 +2881,7 @@ def kernel_init_vgeom_fields( vgeoms_vface_start: ti.types.ndarray(), vgeoms_vvert_end: ti.types.ndarray(), vgeoms_vface_end: ti.types.ndarray(), + vgeoms_color: ti.types.ndarray(), # taichi variables vgeoms_info: array_class.VGeomsInfo, static_rigid_sim_config: ti.template(), @@ -2902,6 +2904,8 @@ def kernel_init_vgeom_fields( vgeoms_info.vface_num[i] = vgeoms_vface_end[i] - vgeoms_vface_start[i] vgeoms_info.link_idx[i] = vgeoms_link_idx[i] + for j in ti.static(range(4)): + vgeoms_info.color[i][j] = vgeoms_color[i, j] @ti.kernel @@ -3433,7 +3437,9 @@ def kernel_rigid_entity_inverse_kinematics( rot_mask = ti.Vector([rot_mask_[0], rot_mask_[1], rot_mask_[2]], dt=gs.ti_float) n_error_dims = 6 * n_links - for i_b in envs_idx: + for i_b_ in range(envs_idx.shape[0]): + i_b = envs_idx[i_b_] + # save original qpos for i_q in range(rigid_entity.n_qs): rigid_entity._IK_qpos_orig[i_q, i_b] = rigid_global_info.qpos[i_q + rigid_entity._q_start, i_b] @@ -4047,7 +4053,9 @@ def kernel_forward_kinematics_links_geoms( rigid_global_info: array_class.RigidGlobalInfo, static_rigid_sim_config: ti.template(), ): - for i_b in envs_idx: + for i_b_ in range(envs_idx.shape[0]): + i_b = envs_idx[i_b_] + func_update_cartesian_space( i_b=i_b, links_state=links_state, @@ -4488,7 +4496,9 @@ def kernel_forward_kinematics_entity( rigid_global_info: array_class.RigidGlobalInfo, static_rigid_sim_config: ti.template(), ): - for i_b in envs_idx: + for i_b_ in range(envs_idx.shape[0]): + i_b = envs_idx[i_b_] + func_forward_kinematics_entity( i_e, i_b, @@ -4518,7 +4528,6 @@ def func_forward_kinematics_entity( rigid_global_info: array_class.RigidGlobalInfo, static_rigid_sim_config: ti.template(), ): - for i_l in range(entities_info.link_start[i_e], entities_info.link_end[i_e]): I_l = [i_l, i_b] if ti.static(static_rigid_sim_config.batch_links_info) else i_l @@ -4631,7 +4640,6 @@ def func_forward_velocity_entity( rigid_global_info: array_class.RigidGlobalInfo, static_rigid_sim_config: ti.template(), ): - for i_l in range(entities_info.link_start[i_e], entities_info.link_end[i_e]): I_l = [i_l, i_b] if ti.static(static_rigid_sim_config.batch_links_info) else i_l @@ -4708,7 +4716,9 @@ def kernel_update_geoms( rigid_global_info: array_class.RigidGlobalInfo, static_rigid_sim_config: ti.template(), ): - for i_b in envs_idx: + for i_b_ in range(envs_idx.shape[0]): + i_b = envs_idx[i_b_] + func_update_geoms( i_b, entities_info, diff --git a/genesis/ext/gs-madrona b/genesis/ext/gs-madrona new file mode 160000 index 0000000000..40db893310 --- /dev/null +++ b/genesis/ext/gs-madrona @@ -0,0 +1 @@ +Subproject commit 40db893310b66993f563c305d10f7425992f9ac5 diff --git a/genesis/options/renderers.py b/genesis/options/renderers.py index f538702e0e..65c483bcfe 100644 --- a/genesis/options/renderers.py +++ b/genesis/options/renderers.py @@ -6,7 +6,7 @@ from .surfaces import Surface -class Renderer(Options): +class RendererOptions(Options): """ This is the base class for all `gs.renderers.*` classes. Note that this is not an actual renderer, but rather a renderer configuration specifying which renderer to use and its parameters. @@ -15,7 +15,7 @@ class Renderer(Options): pass -class Rasterizer(Renderer): +class Rasterizer(RendererOptions): """ Rasterizer renderer. This has no parameter to be configured. @@ -27,7 +27,7 @@ class Rasterizer(Renderer): pass -class RayTracer(Renderer): +class RayTracer(RendererOptions): """ RayTracer renderer. @@ -96,3 +96,20 @@ def __init__(self, **data): self.env_quat = gs.utils.geom.xyz_to_quat(np.array(self.env_euler), rpy=True, degrees=True) else: gs.logger.warning("`env_euler` is ignored when `env_quat` is specified.") + + +class BatchRenderer(RendererOptions): + """ + BatchRenderer renderer. + + Note + ---- + This renderer is used to render the scene in a batch. + + Parameters + ---------- + use_rasterizer : bool, optional + Whether to use the rasterizer renderer. Defaults to False. + """ + + use_rasterizer: bool = False diff --git a/genesis/utils/array_class.py b/genesis/utils/array_class.py index 026b78e28e..c7b4338556 100644 --- a/genesis/utils/array_class.py +++ b/genesis/utils/array_class.py @@ -1737,6 +1737,7 @@ class StructVgeomsInfo: vface_num: V_ANNOTATION vface_start: V_ANNOTATION vface_end: V_ANNOTATION + color: V_ANNOTATION def get_vgeoms_info(solver): @@ -1751,6 +1752,7 @@ def get_vgeoms_info(solver): "vface_num": V(dtype=gs.ti_int, shape=shape), "vface_start": V(dtype=gs.ti_int, shape=shape), "vface_end": V(dtype=gs.ti_int, shape=shape), + "color": V(dtype=gs.ti_vec4, shape=shape), } if use_ndarray: diff --git a/genesis/utils/geom.py b/genesis/utils/geom.py index f7b6910d93..cfc175003c 100644 --- a/genesis/utils/geom.py +++ b/genesis/utils/geom.py @@ -1139,8 +1139,104 @@ def scale_to_T(scale): return T +def z_up_to_R(z, up=np.array([0, 0, 1]), out=None): + if isinstance(z, torch.Tensor): + return _tc_z_up_to_R(z, up, out) + else: + return _np_z_up_to_R(z, up, out) + + +def _tc_z_up_to_R(z, up=None, out=None): + B = z.shape[:-1] + if out is None: + R = torch.empty((*B, 3, 3), dtype=z.dtype, device=z.device) + else: + assert out.shape == (*B, 3, 3) + R = out + + # Compute z norms + z_norm = torch.sqrt(torch.sum(z.reshape(-1, 3) ** 2, dim=-1)).reshape(B) + + # Set z as the third column of rotation matrix + R[..., 2] = z + + # Handle batch dimension properly + if z.ndim > 1: + # For batched inputs, use vectorized operations + # Normalize z vectors + z_normalized = z / z_norm.unsqueeze(-1).clamp(min=gs.EPS) + + # Handle zero norm cases + zero_mask = z_norm < gs.EPS + if zero_mask.any(): + z_normalized[zero_mask] = torch.tensor([0.0, 1.0, 0.0], device=z.device, dtype=z.dtype) + + # Compute x vectors (first column) + if up is not None: + # Handle up vector broadcasting + if up.ndim == 1: + up_expanded = up.unsqueeze(0).expand(z.shape[0], -1) + else: + up_expanded = up + x = torch.cross(up_expanded, z_normalized, dim=-1) + else: + # Default up vector case + x = torch.stack( + [z_normalized[..., 1], -z_normalized[..., 0], torch.zeros_like(z_normalized[..., 0])], dim=-1 + ) + + # Normalize x vectors + x_norm = torch.norm(x, dim=-1, keepdim=True) + x_normalized = x / x_norm.clamp(min=gs.EPS) + + # Handle zero x norm cases + zero_x_mask = x_norm.squeeze(-1) < gs.EPS + if zero_x_mask.any(): + # For zero x norm, set identity matrix + R[zero_x_mask] = torch.eye(3, device=z.device, dtype=z.dtype) + # Continue with non-zero cases + valid_mask = ~zero_x_mask + if valid_mask.any(): + z_valid = z_normalized[valid_mask] + x_valid = x_normalized[valid_mask] + y_valid = torch.cross(z_valid, x_valid, dim=-1) + + # Stack vectors and assign to valid positions + R_valid = torch.stack([x_valid, y_valid, z_valid], dim=-1) + R[valid_mask] = R_valid + else: + # All x norms are valid, compute y vectors + y = torch.cross(z_normalized, x_normalized, dim=-1) + + # Stack vectors to form rotation matrices + R[:] = torch.stack([x_normalized, y, z_normalized], dim=-1) + else: + # Single vector case + x, y, z = R.T + + if z_norm > gs.EPS: # Use hardcoded EPS for consistency + z[:] = z / z_norm + else: + z[:] = torch.tensor([0.0, 1.0, 0.0], device=z.device, dtype=z.dtype) + + if up is not None: + x[:] = torch.linalg.cross(up, z) + else: + x[0] = z[1] + x[1] = -z[0] + x[2] = 0.0 + x_norm = torch.norm(x) + if x_norm > gs.EPS: # Use hardcoded EPS for consistency + x /= x_norm + y[:] = torch.linalg.cross(z, x) + else: + R[:] = torch.eye(3, device=z.device, dtype=z.dtype) + + return R + + @nb.jit(nopython=True, cache=True) -def z_up_to_R(z, up=None, out=None): +def _np_z_up_to_R(z, up=None, out=None): B = z.shape[:-1] if out is None: out_ = np.empty((*B, 3, 3), dtype=z.dtype) @@ -1162,7 +1258,7 @@ def z_up_to_R(z, up=None, out=None): z[:] = 0.0, 1.0, 0.0 if up is not None: - x[:] = np.cross(up, z) + x[:] = np.cross(up[i], z) else: x[0] = z[1] x[1] = -z[0] @@ -1178,27 +1274,28 @@ def z_up_to_R(z, up=None, out=None): def pos_lookat_up_to_T(pos, lookat, up, *, dtype=np.float32): - pos = np.asarray(pos, dtype=dtype) - lookat = np.asarray(lookat, dtype=dtype) - up = np.asarray(up, dtype=dtype) - - T = np.zeros((4, 4), dtype=dtype) - T[3, 3] = 1.0 - T[:3, 3] = pos - - z = pos - lookat - z_norm = np.linalg.norm(z) - if z_norm < gs.EPS: - z = np.array([0.0, 1.0, 0.0], dtype=dtype) - z_up_to_R(z, up=up, out=T[:3, :3]) - - return T + if all(isinstance(e, torch.Tensor) for e in (pos, lookat, up) if e is not None): + z = pos - lookat + if (torch.abs(z).max() < gs.EPS).all(): + z = torch.tensor((1.0, 0.0, 0.0), dtype=pos.dtype, device=pos.device) + R = z_up_to_R(z, up=up) + return trans_R_to_T(pos, R) + elif all(isinstance(e, np.ndarray) for e in (pos, lookat, up) if e is not None): + z = pos - lookat + if (np.abs(z).max() < gs.EPS).all(): + z = np.array((1.0, 0.0, 0.0), dtype=pos.dtype) + R = z_up_to_R(z, up=up) + return trans_R_to_T(pos, R) + else: + gs.raise_exception( + f"all of the inputs must be torch.Tensor or np.ndarray. got: {type(pos)=}, {type(lookat)=}, {type(up)=}" + ) def T_to_pos_lookat_up(T): - pos = T[:3, 3] - lookat = T[:3, 3] - T[:3, 2] - up = T[:3, 1] + pos = T[..., :3, 3] + lookat = T[..., :3, 3] - T[..., :3, 2] + up = T[..., :3, 1] return pos, lookat, up diff --git a/genesis/utils/image_exporter.py b/genesis/utils/image_exporter.py new file mode 100644 index 0000000000..771d25191d --- /dev/null +++ b/genesis/utils/image_exporter.py @@ -0,0 +1,139 @@ +import os +import cv2 +import numpy as np +import torch +from functools import partial +from concurrent.futures import ThreadPoolExecutor + +import genesis as gs +from genesis.utils.misc import tensor_to_array + + +def _export_frame_rgb_camera(i_env, export_dir, i_cam, i_step, rgb): + # Take the rgb channel in case the rgb tensor has RGBA channel. + rgb = np.flip(tensor_to_array(rgb[i_env, ..., :3]), axis=-1) + cv2.imwrite(f"{export_dir}/rgb_cam{i_cam}_env{i_env}_{i_step:03d}.png", rgb) + + +def _export_frame_depth_camera(i_env, export_dir, i_cam, i_step, depth): + depth = tensor_to_array(depth[i_env]) + cv2.imwrite(f"{export_dir}/depth_cam{i_cam}_env{i_env}_{i_step:03d}.png", depth) + + +class FrameImageExporter: + """ + This class enables exporting images from all cameras and all environments in batch and in parallel, unlike + `Camera.(start|stop)_recording` API, which only allows for exporting images from a single camera and environment. + """ + + def __init__(self, export_dir, depth_clip_max=100, depth_scale="log"): + self.export_dir = export_dir + if not os.path.exists(export_dir): + os.makedirs(export_dir) + self.depth_clip_max = depth_clip_max + self.depth_scale = depth_scale + + def _normalize_depth(self, depth): + """Normalize depth values for visualization. + + Args: + depth: Tensor of depth values + + Returns: + Normalized depth tensor as uint8 + """ + # Clip depth values + depth = depth.clamp(0.0, self.depth_clip_max) + + # Apply scaling if specified + if self.depth_scale == "log": + depth = torch.log(depth + 1) + + # Calculate min/max for each image in the batch + depth_min = depth.amin(dim=(-3, -2), keepdim=True) + depth_max = depth.amax(dim=(-3, -2), keepdim=True) + + # Normalize to 0-255 range + return torch.where( + depth_max - depth_min > gs.EPS, ((depth_max - depth) / (depth_max - depth_min) * 255).to(torch.uint8), 0 + ) + + def export_frame_all_cameras(self, i_step, camera_idx=None, rgb=None, depth=None): + """ + Export frames for all cameras. + + Args: + i_step: The current step index. + camera_idx: array of indices of cameras to export. If None, all cameras are exported. + rgb: rgb image is a sequence of tensors of shape (n_envs, H, W, 3). + depth: Depth image is a sequence of tensors of shape (n_envs, H, W). + """ + if rgb is None and depth is None: + gs.logger.info("No rgb or depth images to export") + return + if rgb is not None and (not isinstance(rgb, (tuple, list)) or not rgb): + gs.raise_exception("'rgb' must be a non-empty sequence of tensors.") + if depth is not None and (not isinstance(depth, (tuple, list)) or not depth): + gs.raise_exception("'depth' must be a non-empty sequence of tensors.") + if camera_idx is None: + camera_idx = range(len(depth or rgb)) + for i_cam in camera_idx: + rgb_cam, depth_cam = None, None + if rgb is not None: + rgb_cam = rgb[i_cam] + if depth is not None: + depth_cam = depth[i_cam] + self.export_frame_single_camera(i_step, i_cam, rgb_cam, depth_cam) + + def export_frame_single_camera(self, i_step, i_cam, rgb=None, depth=None): + """ + Export frames for a single camera. + + Args: + i_step: The current step index. + i_cam: The index of the camera. + rgb: rgb image tensor of shape (n_envs, H, W, 3). + depth: Depth tensor of shape (n_envs, H, W). + """ + if rgb is not None: + rgb = torch.as_tensor(rgb, dtype=torch.uint8, device=gs.device) + + # Unsqueeze rgb to (n_envs, H, W, 3) + if rgb.ndim == 3: + rgb = rgb.unsqueeze(0) + if rgb.ndim != 4 or rgb.shape[-1] != 3: + gs.raise_exception("'rgb' must be a tensor of shape (n_envs, H, W, 3)") + + rgb_job = partial( + _export_frame_rgb_camera, + export_dir=self.export_dir, + i_cam=i_cam, + i_step=i_step, + rgb=rgb, + ) + + with ThreadPoolExecutor() as executor: + executor.map(rgb_job, np.arange(len(rgb))) + + if depth is not None: + depth = torch.as_tensor(depth, dtype=torch.float32, device=gs.device) + + # Unsqueeze depth to (n_envs, H, W, 1) + if depth.ndim == 3: + depth = depth.unsqueeze(0) + elif depth.ndim == 2: + depth = depth.reshape((1, *depth.shape, 1)) + depth = self._normalize_depth(depth) + if depth.ndim != 4 or depth.shape[-1] != 1: + gs.raise_exception("'rgb' must be a tensor of shape (n_envs, H, W, 1)") + + depth_job = partial( + _export_frame_depth_camera, + export_dir=self.export_dir, + i_cam=i_cam, + i_step=i_step, + depth=depth, + ) + + with ThreadPoolExecutor() as executor: + executor.map(depth_job, np.arange(len(depth))) diff --git a/genesis/utils/misc.py b/genesis/utils/misc.py index 5e2fc75085..4280ddf415 100644 --- a/genesis/utils/misc.py +++ b/genesis/utils/misc.py @@ -205,9 +205,8 @@ def get_device(backend: gs_backend): total_mem = device_property.total_memory / 1024**3 else: # pytorch tensors on cpu # logger may not be configured at this point - getattr(gs, "logger", LOGGER).warning( - "No Intel XPU device available. Falling back to CPU for torch device." - ) + logger = getattr(gs, "logger", None) or LOGGER + logger.warning("No Intel XPU device available. Falling back to CPU for torch device.") device, device_name, total_mem, _ = get_device(gs_backend.cpu) elif backend == gs_backend.gpu: diff --git a/genesis/utils/path_planing.py b/genesis/utils/path_planing.py index d9563f9d87..73b0bcf210 100644 --- a/genesis/utils/path_planing.py +++ b/genesis/utils/path_planing.py @@ -201,7 +201,9 @@ def _kernel_check_collision( obj_geom_start: ti.i32, obj_geom_end: ti.i32, ): - for i_b in envs_idx: + for i_b_ in range(envs_idx.shape[0]): + i_b = envs_idx[i_b_] + collision_detected = self._func_check_collision( ignore_geom_pairs, i_b, @@ -354,7 +356,9 @@ def _kernel_rrt_step1( - add new node - set the steer result (to prepare for collision checking) """ - for i_b in envs_idx: + for i_b_ in range(envs_idx.shape[0]): + i_b = envs_idx[i_b_] + if self._rrt_is_active[i_b]: random_sample = ti.Vector( [ @@ -434,7 +438,9 @@ def _kernel_rrt_step2( - if collision is detected, remove the new node - if collision is not detected, check if the new node is within goal configuration """ - for i_b in envs_idx: + for i_b_ in range(envs_idx.shape[0]): + i_b = envs_idx[i_b_] + if self._rrt_is_active[i_b]: is_collision_detected = False if not ignore_collision: @@ -680,7 +686,9 @@ def _kernel_rrt_connect_step1( - add new node - set the steer result (to prepare for collision checking) """ - for i_b in envs_idx: + for i_b_ in range(envs_idx.shape[0]): + i_b = envs_idx[i_b_] + if self._rrt_is_active[i_b]: random_sample = ti.Vector( [ @@ -777,7 +785,9 @@ def _kernel_rrt_connect_step2( - if collision is detected, remove the new node - if collision is not detected, check if the new node is within goal configuration """ - for i_b in envs_idx: + for i_b_ in range(envs_idx.shape[0]): + i_b = envs_idx[i_b_] + if self._rrt_is_active[i_b]: is_collision_detected = False if not ignore_collision: diff --git a/genesis/vis/batch_renderer.py b/genesis/vis/batch_renderer.py new file mode 100644 index 0000000000..46837547ff --- /dev/null +++ b/genesis/vis/batch_renderer.py @@ -0,0 +1,218 @@ +import enum +import math + +import numpy as np +import torch + +import genesis as gs +from genesis.repr_base import RBC + +try: + from gs_madrona.renderer_gs import MadronaBatchRendererAdapter +except ImportError as e: + gs.raise_exception_from("Madrona batch renderer is only supported on Linux x86-64.", e) + + +class IMAGE_TYPE(enum.IntEnum): + RGB = 0 + DEPTH = 3 + NORMAL = 1 + SEGMENTATION = 2 + + +class Light: + def __init__(self, pos, dir, intensity, directional, castshadow, cutoff): + self._pos = pos + self._dir = dir + self._intensity = intensity + self._directional = directional + self._castshadow = castshadow + self._cutoff = cutoff + + @property + def pos(self): + return self._pos + + @property + def dir(self): + return self._dir + + @property + def intensity(self): + return self._intensity + + @property + def directional(self): + return self._directional + + @property + def castshadow(self): + return self._castshadow + + @property + def cutoffRad(self): + return math.radians(self._cutoff) + + @property + def cutoffDeg(self): + return self._cutoff + + +class BatchRenderer(RBC): + """ + This class is used to manage batch rendering + """ + + def __init__(self, visualizer, renderer_options): + self._visualizer = visualizer + self._lights = gs.List() + self._renderer_options = renderer_options + + self._data_cache = {} + self._t = -1 + + def add_light(self, pos, dir, intensity, directional, castshadow, cutoff): + self._lights.append(Light(pos, dir, intensity, directional, castshadow, cutoff)) + + def build(self): + """ + Build all cameras in the batch and initialize Moderona renderer + """ + if len(self._visualizer._cameras) == 0: + raise ValueError("No cameras to render") + + if gs.backend != gs.cuda: + gs.raise_exception("BatchRenderer requires CUDA backend.") + + cameras = self._visualizer._cameras + lights = self._lights + rigid = self._visualizer.scene.rigid_solver + n_envs = max(self._visualizer.scene.n_envs, 1) + res = cameras[0].res + gpu_id = gs.device.index + use_rasterizer = self._renderer_options.use_rasterizer + + # Cameras + n_cameras = len(cameras) + cameras_pos = torch.stack([camera.get_pos() for camera in cameras], dim=1) + cameras_quat = torch.stack([camera.get_quat() for camera in cameras], dim=1) + cameras_fov = torch.tensor([camera.fov for camera in cameras], dtype=gs.tc_float, device=gs.device) + + # Build taichi arrays to store light properties once. If later we need to support dynamic lights, we should + # consider storing light properties as taichi fields in Genesis. + n_lights = len(lights) + light_pos = torch.tensor([light.pos for light in self._lights], dtype=gs.tc_float) + light_dir = torch.tensor([light.dir for light in self._lights], dtype=gs.tc_float) + light_intensity = torch.tensor([light.intensity for light in self._lights], dtype=gs.tc_float) + light_directional = torch.tensor([light.directional for light in self._lights], dtype=gs.tc_int) + light_castshadow = torch.tensor([light.castshadow for light in self._lights], dtype=gs.tc_int) + light_cutoff = torch.tensor([light.cutoffRad for light in self._lights], dtype=gs.tc_float) + + self._renderer = MadronaBatchRendererAdapter( + rigid, gpu_id, n_envs, n_cameras, n_lights, cameras_fov, *res, False, use_rasterizer + ) + self._renderer.init( + rigid, + cameras_pos, + cameras_quat, + light_pos, + light_dir, + light_intensity, + light_directional, + light_castshadow, + light_cutoff, + ) + + def update_scene(self): + self._visualizer._context.update() + + def render(self, rgb=True, depth=False, segmentation=False, normal=False, force_render=False, aliasing=False): + """ + Render all cameras in the batch. + + Parameters + ---------- + rgb : bool, optional + Whether to render the rgb image. + depth : bool, optional + Whether to render the depth image. + segmentation : bool, optional + Whether to render the segmentation image. + normal : bool, optional + Whether to render the normal image. + force_render : bool, optional + Whether to force render the scene. + aliasing : bool, optional + Whether to apply anti-aliasing. + + Returns + ------- + rgb_arr : tuple of tensors + The sequence of rgb images associated with each camera. + depth_arr : tuple of tensors + The sequence of depth images associated with each camera. + """ + if normal: + raise NotImplementedError("Normal rendering not supported from now") + if segmentation: + raise NotImplementedError("Segmentation rendering not supported from now") + + # Clear cache if requested or necessary + if force_render or self._t < self._visualizer.scene.t: + self._data_cache.clear() + + # Fetch available cached data + cache_key = (aliasing,) + rgb_arr = self._data_cache.get((IMAGE_TYPE.RGB, cache_key), None) + depth_arr = self._data_cache.get((IMAGE_TYPE.DEPTH, cache_key), None) + + # Force disabling rendering whenever cached data is already available + rgb_ = rgb and rgb_arr is None + depth_ = depth and depth_arr is None + + # Early return if there is nothing to do + if not (rgb_ or depth_): + return rgb_arr if rgb else None, depth_arr if depth else None, None, None + + # Update scene + self.update_scene() + + # Render frame + cameras_pos = torch.stack([camera.get_pos() for camera in self._visualizer._cameras], dim=1) + cameras_quat = torch.stack([camera.get_quat() for camera in self._visualizer._cameras], dim=1) + render_options = np.array((rgb_, depth_, False, False, aliasing), dtype=np.uint32) + rgba_arr_all, depth_arr_all = self._renderer.render( + self._visualizer.scene.rigid_solver, cameras_pos, cameras_quat, render_options + ) + + # Post-processing: Remove alpha channel from RGBA, squeeze env dim if necessary, and split along camera dim + buffers = [rgba_arr_all[..., :3], depth_arr_all] + for i, data in enumerate(buffers): + if data is not None: + data = data.swapaxes(0, 1) + if self._visualizer.scene.n_envs == 0: + data = data.squeeze(1) + buffers[i] = tuple(data) + + # Update cache + self._t = self._visualizer.scene.t + if rgb_: + rgb_arr = self._data_cache[(IMAGE_TYPE.RGB, cache_key)] = buffers[0] + if depth_: + depth_arr = self._data_cache[(IMAGE_TYPE.DEPTH, cache_key)] = buffers[1] + + return rgb_arr, depth_arr, None, None + + def destroy(self): + self._lights.clear() + self._data_cache.clear() + if self._renderer is not None: + del self._renderer.madrona + self._renderer = None + + def reset(self): + self._t = -1 + + @property + def lights(self): + return self._lights diff --git a/genesis/vis/camera.py b/genesis/vis/camera.py index 6fff5b38a4..49a3ea93cb 100644 --- a/genesis/vis/camera.py +++ b/genesis/vis/camera.py @@ -1,9 +1,11 @@ import inspect import os import time +import math import cv2 import numpy as np +import torch import genesis as gs import genesis.utils.geom as gu @@ -11,6 +13,18 @@ from genesis.utils.misc import tensor_to_array +# quat for Madrona needs to be transformed to y-forward +def _T_to_quat_for_madrona(T): + if not isinstance(T, torch.Tensor): + gs.raise_exception(f"the input must be torch.Tensor. got: {type(T)=}") + + R = T[..., :3, :3].contiguous() + quat = gu.R_to_quat(R) + + w, x, y, z = quat[..., 0], quat[..., 1], quat[..., 2], quat[..., 3] + return torch.stack([x + w, x - w, y - z, y + z], dim=1) / math.sqrt(2.0) + + class Camera(Sensor): """ A camera which can be used to render RGB, depth, and segmentation images. @@ -85,22 +99,21 @@ def __init__( self._denoise = denoise self._near = near self._far = far - self._pos = pos - self._lookat = lookat - self._up = up - self._transform = transform + self._initial_pos = torch.as_tensor(pos, dtype=gs.tc_float, device=gs.device) + self._initial_lookat = torch.as_tensor(lookat, dtype=gs.tc_float, device=gs.device) + self._initial_up = torch.as_tensor(up, dtype=gs.tc_float, device=gs.device) + self._initial_transform = None + if transform is not None: + self._initial_transform = torch.as_tensor(transform, dtype=gs.tc_float, device=gs.device) self._aspect_ratio = self._res[0] / self._res[1] self._visualizer = visualizer self._is_built = False self._attached_link = None self._attached_offset_T = None - self._attached_env_idx = None self._in_recording = False self._recorded_imgs = [] - self._init_pos = np.array(pos) - self._followed_entity = None self._follow_fixed_axis = None self._follow_smoothing = None @@ -110,29 +123,35 @@ def __init__( gs.raise_exception(f"Invalid camera model: {self._model}") if self._focus_dist is None: - self._focus_dist = np.linalg.norm(np.array(lookat) - np.array(pos)) + self._focus_dist = np.linalg.norm(np.asarray(lookat) - np.asarray(pos)) - def _build(self): + def build(self): + self._batch_renderer = self._visualizer.batch_renderer self._rasterizer = self._visualizer.rasterizer self._raytracer = self._visualizer.raytracer - self._rgb_stacked = self._visualizer._context.env_separate_rigid - self._other_stacked = self._visualizer._context.env_separate_rigid - - if self._rasterizer is not None: - self._rasterizer.add_camera(self) - if self._raytracer is not None: + self._rasterizer.add_camera(self) + if self._batch_renderer is not None: + self._rgb_stacked = True + self._other_stacked = True + elif self._raytracer is not None: self._raytracer.add_camera(self) - self._rgb_stacked = False # TODO: Raytracer currently does not support batch rendering + self._rgb_stacked = False + self._other_stacked = False + else: + self._rgb_stacked = self._visualizer._context.env_separate_rigid + self._other_stacked = self._visualizer._context.env_separate_rigid self._is_built = True - self.set_pose(self._transform, self._pos, self._lookat, self._up) + self.setup_initial_env_poses() - def attach(self, rigid_link, offset_T, env_idx: int | None = None): + def attach(self, rigid_link, offset_T): """ Attach the camera to a rigid link in the scene. - Once attached, the camera's position and orientation can be updated relative to the attached link using `move_to_attach()`. This is useful for mounting the camera to dynamic entities like robots or articulated objects. + Once attached, the camera's position and orientation can be updated relative to the attached link using + `move_to_attach()`. This is useful for mounting the camera to dynamic entities like robots or articulated + objects. Parameters ---------- @@ -140,75 +159,177 @@ def attach(self, rigid_link, offset_T, env_idx: int | None = None): The rigid link to which the camera should be attached. offset_T : np.ndarray, shape (4, 4) The transformation matrix specifying the camera's pose relative to the rigid link. - env_idx : int - The environment index this camera should be tied to. Offsets the `offset_T` accordingly. Must be specified - if running parallel environments - - Raises - ------ - Exception - If running parallel simulations but env_idx is not specified. - Exception - If invalid env_idx is specified (env_idx >= n_envs) """ + if self._followed_entity is not None: + gs.raise_exception("Impossible to attach a camera that is already following an entity.") self._attached_link = rigid_link - self._attached_offset_T = offset_T - if self._visualizer._scene.n_envs > 0 and env_idx is None: - gs.raise_exception("Must specify env_idx when running parallel simulations") - if env_idx is not None: - n_envs = self._visualizer._scene.n_envs - if env_idx >= n_envs: - gs.raise_exception(f"Invalid env_idx {env_idx} for camera, configured for {n_envs} environments") - self._attached_env_idx = env_idx + self._attached_offset_T = torch.as_tensor(offset_T, dtype=gs.tc_float, device=gs.device) def detach(self): """ Detach the camera from the currently attached rigid link. - After detachment, the camera will stop following the motion of the rigid link and maintain its current world pose. Calling this method has no effect if the camera is not currently attached. + After detachment, the camera will stop following the motion of the rigid link and maintain its current world + pose. Calling this method has no effect if the camera is not currently attached. """ self._attached_link = None self._attached_offset_T = None - self._attached_env_idx = None - @gs.assert_built - def move_to_attach(self): + def move_to_attach(self, env_idx=None): """ Move the camera to follow the currently attached rigid link. - This method updates the camera's pose using the transform of the attached rigid link combined with the specified offset. It should only be called after `attach()` has been used. This method is not compatible with simulations running multiple environments in parallel. + This method updates the camera's pose using the transform of the attached rigid link combined with the + specified offset. It should only be called after `attach()` has been used. Raises ------ Exception - If the camera has not been mounted using `attach()`. + If the camera has not been attached to a rigid link. """ + # move_to_attach can be called from update_visual_states(), which could be called either before or after build(), + # but set_pose() is only allowed after build(), so we need to check if the camera is built here, and early out if not. + if not self._is_built: + return + if self._attached_link is None: - gs.raise_exception(f"The camera hasn't been mounted!") + gs.raise_exception("Camera not attached") - link_pos = tensor_to_array(self._attached_link.get_pos(envs_idx=self._attached_env_idx)) - link_quat = tensor_to_array(self._attached_link.get_quat(envs_idx=self._attached_env_idx)) - if self._attached_env_idx is not None: - link_pos = link_pos[0] + self._visualizer._scene.envs_offset[self._attached_env_idx] - link_quat = link_quat[0] + link_pos = self._attached_link.get_pos(env_idx) + link_quat = self._attached_link.get_quat(env_idx) link_T = gu.trans_quat_to_T(link_pos, link_quat) - transform = link_T @ self._attached_offset_T + transform = torch.matmul(link_T, self._attached_offset_T) self.set_pose(transform=transform) + def follow_entity(self, entity, fixed_axis=(None, None, None), smoothing=None, fix_orientation=False): + """ + Set the camera to follow a specified entity. + + Parameters + ---------- + entity : genesis.Entity + The entity to follow. + fixed_axis : (float, float, float), optional + The fixed axis for the camera's movement. For each axis, if None, the camera will move freely. If a float, + the viewer will be fixed on at that value. For example, [None, None, None] will allow the camera to move + freely while following, [None, None, 0.5] will fix the viewer's z-axis at 0.5. + smoothing : float, optional + The smoothing factor for the camera's movement. If None, no smoothing will be applied. + fix_orientation : bool, optional + If True, the camera will maintain its orientation relative to the world. If False, the camera will look at + the base link of the entity. + """ + if self._attached_link is not None: + gs.raise_exception("Impossible to following an entity with a camera that is already attached.") + + self._followed_entity = entity + self._follow_fixed_axis = fixed_axis + self._follow_smoothing = smoothing + self._follow_fix_orientation = fix_orientation + + def unfollow_entity(self): + """ + Stop following any entity with the camera. + + Calling this method has no effect if the camera is not currently following any entity. + """ + self._followed_entity = None + self._follow_fixed_axis = None + self._follow_smoothing = None + self._follow_fix_orientation = None + + @gs.assert_built + def update_following(self): + """ + Update the camera position to follow the specified entity. + """ + if self._followed_entity is None: + gs.raise_exception("No entity to follow. Please call `camera.follow_entity(entity)` first.") + + # Keep the camera orientation fixed by overriding the lookat point if requested + if self._follow_fix_orientation: + camera_transform = self._multi_env_transform_tensor.clone() + camera_lookat = None + camera_pos = camera_transform[:, :3, 3] + else: + camera_lookat = self._multi_env_lookat_tensor.clone() + camera_pos = self._multi_env_pos_tensor.clone() + + # Smooth camera movement with a low-pass filter, in particular Exponential Moving Average (EMA) if requested + entity_pos = self._followed_entity.get_pos() + camera_pos -= self._initial_pos + if self._follow_smoothing is not None: + camera_pos[:] = self._follow_smoothing * camera_pos + (1.0 - self._follow_smoothing) * entity_pos + if camera_lookat is not None: + camera_lookat[:] = self._follow_smoothing * camera_lookat + (1.0 - self._follow_smoothing) * entity_pos + else: + camera_pos[:] = entity_pos + camera_pos += self._initial_pos + + # Fix the camera's position along the specified axis if requested + for i, fixed_axis in enumerate(self._follow_fixed_axis): + if fixed_axis is not None: + camera_pos[:, i] = fixed_axis + + # Update the pose of all camera at once + if self._follow_fix_orientation: + self.set_pose(transform=camera_transform) + else: + self.set_pose(pos=camera_pos, lookat=camera_lookat) + @gs.assert_built - def read(self): + def _batch_render( + self, + rgb=True, + depth=False, + segmentation=False, + normal=False, + force_render=False, + antialiasing=False, + ): """ - Obtain the RGB camera view. - This is a temporary implementation to make Camera a Sensor. + Render the camera view with batch renderer. """ - rgb, _, _, _ = self.render() - return rgb + assert self._visualizer._batch_renderer is not None + rgb_arr, depth_arr, seg_arr, normal_arr = self._batch_renderer.render( + rgb, depth, segmentation, normal, force_render, antialiasing + ) + # The first dimension of the array is camera. + # If n_envs > 0, the second dimension of the output is env. + # If n_envs == 0, the second dimension of the output is camera. + # Only return the current camera's image + if rgb_arr: + rgb_arr = rgb_arr[self._idx] + if depth: + depth_arr = depth_arr[self._idx] + if segmentation: + seg_arr = seg_arr[self._idx] + if normal: + normal_arr = normal_arr[self._idx] + return rgb_arr, depth_arr, seg_arr, normal_arr @gs.assert_built - def render(self, rgb=True, depth=False, segmentation=False, colorize_seg=False, normal=False): + def render( + self, + rgb=True, + depth=False, + segmentation=False, + colorize_seg=False, + normal=False, + force_render=False, + antialiasing=False, + ): """ - Render the camera view. Note that the segmentation mask can be colorized, and if not colorized, it will store an object index in each pixel based on the segmentation level specified in `VisOptions.segmentation_level`. For example, if `segmentation_level='link'`, the segmentation mask will store `link_idx`, which can then be used to retrieve the actual link objects using `scene.rigid_solver.links[link_idx]`. - If `env_separate_rigid` in `VisOptions` is set to True, each component will return a stack of images, with the number of images equal to `len(rendered_envs_idx)`. + Render the camera view. + + Note + ---- + The segmentation mask can be colorized, and if not colorized, it will store an object index in each pixel based + on the segmentation level specified in `VisOptions.segmentation_level`. + For example, if `segmentation_level='link'`, the segmentation mask will store `link_idx`, which can then be + used to retrieve the actual link objects using `scene.rigid_solver.links[link_idx]`. If `env_separate_rigid` + in `VisOptions` is set to True, each component will return a stack of images, with the number of images equal + to `len(rendered_envs_idx)`. Parameters ---------- @@ -222,6 +343,10 @@ def render(self, rgb=True, depth=False, segmentation=False, colorize_seg=False, If True, the segmentation mask will be colorized. normal : bool, optional Whether to render the surface normal. + force_render : bool, optional + Whether to force rendering even if the scene has not changed. + antialiasing : bool, optional + Whether to apply anti-aliasing. Returns ------- @@ -238,48 +363,46 @@ def render(self, rgb=True, depth=False, segmentation=False, colorize_seg=False, if (rgb or depth or segmentation or normal) is False: gs.raise_exception("Nothing to render.") - rgb_arr, depth_arr, seg_idxc_arr, seg_arr, normal_arr = None, None, None, None, None - - if self._followed_entity is not None: - self.update_following() + rgb_arr, depth_arr, seg_arr, seg_color_arr, normal_arr = None, None, None, None, None - if self._raytracer is not None: + if self._batch_renderer is not None: + rgb_arr, depth_arr, seg_idxc_arr, normal_arr = self._batch_render( + rgb, depth, segmentation, normal, force_render, antialiasing + ) + elif self._raytracer is not None: if rgb: self._raytracer.update_scene() rgb_arr = self._raytracer.render_camera(self) if depth or segmentation or normal: - if self._rasterizer is not None: - self._rasterizer.update_scene() - _, depth_arr, seg_idxc_arr, normal_arr = self._rasterizer.render_camera( - self, False, depth, segmentation, normal=normal - ) - else: - gs.raise_exception("Cannot render depth or segmentation image.") - - elif self._rasterizer is not None: + self._rasterizer.update_scene() + _, depth_arr, seg_idxc_arr, normal_arr = self._rasterizer.render_camera( + self, False, depth, segmentation, normal=normal + ) + else: self._rasterizer.update_scene() rgb_arr, depth_arr, seg_idxc_arr, normal_arr = self._rasterizer.render_camera( self, rgb, depth, segmentation, normal=normal ) - else: - gs.raise_exception("No renderer was found.") - if seg_idxc_arr is not None: - if colorize_seg or (self._GUI and self._visualizer.connected_to_display): + if colorize_seg or (self._GUI and self._visualizer.has_display): seg_color_arr = self._rasterizer._context.colorize_seg_idxc_arr(seg_idxc_arr) - if colorize_seg: - seg_arr = seg_color_arr - else: - seg_arr = seg_idxc_arr + seg_arr = seg_color_arr if colorize_seg else seg_idxc_arr + + if self._in_recording or self._GUI and self._visualizer.has_display: + rgb_np = rgb_arr if rgb_arr is None else tensor_to_array(rgb_arr) # succeed rendering, and display image - if self._GUI and self._visualizer.connected_to_display: - title = f"Genesis - Camera {self._idx}" + if self._GUI and self._visualizer.has_display: + depth_np, seg_color_np, normal_np = map( + lambda e: e if e is None else tensor_to_array(e), (depth_arr, seg_color_arr, normal_arr) + ) + title = f"Genesis - Camera {self._idx}" if rgb: - rgb_img = rgb_arr[..., [2, 1, 0]] + # FIXME: Check whether it always render RGB or RGBA ? + rgb_img = np.flip(rgb_np, axis=-1) rgb_env = "" if self._rgb_stacked: rgb_img = rgb_img[0] @@ -288,34 +411,33 @@ def render(self, rgb=True, depth=False, segmentation=False, colorize_seg=False, other_env = " Environment 0" if self._other_stacked else "" if depth: - depth_min = depth_arr.min() - depth_max = depth_arr.max() - depth_normalized = (depth_arr - depth_min) / (depth_max - depth_min) - depth_normalized = 1 - depth_normalized # closer objects appear brighter - depth_img = (depth_normalized * 255).astype(np.uint8) + depth_min = depth_np.min() + depth_max = depth_np.max() + if depth_max - depth_min > gs.EPS: + depth_normalized = (depth_max - depth_np) / (depth_max - depth_min) + depth_img = (depth_normalized * 255).astype(np.uint8) + else: + depth_img = np.zeros_like(depth_arr, dtype=np.uint8) if self._other_stacked: depth_img = depth_img[0] - cv2.imshow(f"{title + other_env} [Depth]", depth_img) if segmentation: - seg_img = seg_color_arr[..., [2, 1, 0]] + seg_img = np.flip(seg_color_np, axis=-1) if self._other_stacked: seg_img = seg_img[0] - cv2.imshow(f"{title + other_env} [Segmentation]", seg_img) if normal: - normal_img = normal_arr[..., [2, 1, 0]] + normal_img = np.flip(normal_np, axis=-1) if self._other_stacked: normal_img = normal_img[0] - cv2.imshow(f"{title + other_env} [Normal]", normal_img) cv2.waitKey(1) - if self._in_recording and rgb_arr is not None: - self._recorded_imgs.append(rgb_arr) + if self._in_recording and rgb_np is not None: + self._recorded_imgs.append(rgb_np) return rgb_arr, depth_arr, seg_arr, normal_arr @@ -349,94 +471,114 @@ def render_pointcloud(self, world_frame=True): mask_arr : np.ndarray The valid depth mask. """ - if self._rasterizer is not None: - self._rasterizer.update_scene() - rgb_arr, depth_arr, seg_idxc_arr, normal_arr = self._rasterizer.render_camera( - self, False, True, False, normal=False - ) - - def opengl_projection_matrix_to_intrinsics(P: np.ndarray, width: int, height: int): - """Convert OpenGL projection matrix to camera intrinsics. - Args: - P (np.ndarray): OpenGL projection matrix. - width (int): Image width. - height (int): Image height - Returns: - np.ndarray: Camera intrinsics. [3, 3] - """ - - fx = P[0, 0] * width / 2 - fy = P[1, 1] * height / 2 - cx = (1.0 - P[0, 2]) * width / 2 - cy = (1.0 + P[1, 2]) * height / 2 - - K = np.array([[fx, 0, cx], [0, fy, cy], [0, 0, 1]]) - return K - - def backproject_depth_to_pointcloud(K: np.ndarray, depth: np.ndarray, pose, world, znear, zfar): - """Convert depth image to pointcloud given camera intrinsics. - Args: - depth (np.ndarray): Depth image. - Returns: - np.ndarray: (x, y, z) Point cloud. [n, m, 3] - """ - _fx = K[0, 0] - _fy = K[1, 1] - _cx = K[0, 2] - _cy = K[1, 2] - - # Mask out invalid depth - mask = np.where((depth > znear) & (depth < zfar * 0.99)) - # zfar * 0.99 for filtering out precision error of float - height, width = depth.shape - y, x = np.meshgrid(np.arange(height, dtype=np.int32), np.arange(width, dtype=np.int32), indexing="ij") - x = x.reshape((-1,)) - y = y.reshape((-1,)) - - # Normalize pixel coordinates - normalized_x = x - _cx - normalized_y = y - _cy - - # Convert to world coordinates - depth_grid = depth[y, x] - world_x = normalized_x * depth_grid / _fx - world_y = normalized_y * depth_grid / _fy - world_z = depth_grid - - pc = np.stack((world_x, world_y, world_z), axis=1) - - point_cloud_h = np.concatenate((pc, np.ones((len(pc), 1), dtype=np.float32)), axis=1) - if world: - point_cloud_world = point_cloud_h @ pose.T - point_cloud_world = point_cloud_world[:, :3].reshape((depth.shape[0], depth.shape[1], 3)) - return point_cloud_world, mask - else: - point_cloud = point_cloud_h[:, :3].reshape((depth.shape[0], depth.shape[1], 3)) - return point_cloud, mask + self._rasterizer.update_scene() + rgb_arr, depth_arr, seg_idxc_arr, normal_arr = self._rasterizer.render_camera( + self, False, True, False, normal=False + ) + + def opengl_projection_matrix_to_intrinsics(P: np.ndarray, width: int, height: int): + """Convert OpenGL projection matrix to camera intrinsics. + Args: + P (np.ndarray): OpenGL projection matrix. + width (int): Image width. + height (int): Image height + Returns: + np.ndarray: Camera intrinsics. [3, 3] + """ + + fx = P[0, 0] * width / 2 + fy = P[1, 1] * height / 2 + cx = (1.0 - P[0, 2]) * width / 2 + cy = (1.0 + P[1, 2]) * height / 2 + + K = np.array([[fx, 0, cx], [0, fy, cy], [0, 0, 1]]) + return K + + def backproject_depth_to_pointcloud(K: np.ndarray, depth: np.ndarray, pose, world, znear, zfar): + """Convert depth image to pointcloud given camera intrinsics. + Args: + depth (np.ndarray): Depth image. + Returns: + np.ndarray: (x, y, z) Point cloud. [n, m, 3] + """ + _fx = K[0, 0] + _fy = K[1, 1] + _cx = K[0, 2] + _cy = K[1, 2] + + # Mask out invalid depth + mask = np.where((depth > znear) & (depth < zfar * 0.99)) + # zfar * 0.99 for filtering out precision error of float + height, width = depth.shape + y, x = np.meshgrid(np.arange(height, dtype=np.int32), np.arange(width, dtype=np.int32), indexing="ij") + x = x.reshape((-1,)) + y = y.reshape((-1,)) + + # Normalize pixel coordinates + normalized_x = x - _cx + normalized_y = y - _cy + + # Convert to world coordinates + depth_grid = depth[y, x] + world_x = normalized_x * depth_grid / _fx + world_y = normalized_y * depth_grid / _fy + world_z = depth_grid + + pc = np.stack((world_x, world_y, world_z), axis=1) + + point_cloud_h = np.concatenate((pc, np.ones((len(pc), 1), dtype=np.float32)), axis=1) + if world: + point_cloud_world = point_cloud_h @ pose.T + point_cloud_world = point_cloud_world[:, :3].reshape((depth.shape[0], depth.shape[1], 3)) + return point_cloud_world, mask + else: + point_cloud = point_cloud_h[:, :3].reshape((depth.shape[0], depth.shape[1], 3)) + return point_cloud, mask - intrinsic_K = opengl_projection_matrix_to_intrinsics( - self._rasterizer._camera_nodes[self.uid].camera.get_projection_matrix(), - width=self.res[0], - height=self.res[1], - ) + intrinsic_K = opengl_projection_matrix_to_intrinsics( + self._rasterizer._camera_nodes[self.uid].camera.get_projection_matrix(), + width=self.res[0], + height=self.res[1], + ) - T_OPENGL_TO_OPENCV = np.array([[1, 0, 0, 0], [0, -1, 0, 0], [0, 0, -1, 0], [0, 0, 0, 1]], dtype=np.float32) - cam_pose = self._rasterizer._camera_nodes[self.uid].matrix @ T_OPENGL_TO_OPENCV + T_OPENGL_TO_OPENCV = np.array([[1, 0, 0, 0], [0, -1, 0, 0], [0, 0, -1, 0], [0, 0, 0, 1]], dtype=np.float32) + cam_pose = self._rasterizer._camera_nodes[self.uid].matrix @ T_OPENGL_TO_OPENCV - pc, mask = backproject_depth_to_pointcloud( - intrinsic_K, depth_arr, cam_pose, world_frame, self.near, self.far - ) + pc, mask = backproject_depth_to_pointcloud(intrinsic_K, depth_arr, cam_pose, world_frame, self.near, self.far) - return pc, mask + return pc, mask + @gs.assert_built + def setup_initial_env_poses(self): + """ + Setup the camera poses for multiple environments. + """ + if self._initial_transform is not None: + assert self._initial_transform.shape == (4, 4) + self._initial_pos, self._initial_lookat, self._initial_up = gu.T_to_pos_lookat_up(self._initial_transform) else: - gs.raise_exception("We need a rasterizer to render depth and then convert it to pount cloud.") + self._initial_transform = gu.pos_lookat_up_to_T(self._initial_pos, self._initial_lookat, self._initial_up) + + n_envs = max(self._visualizer.scene.n_envs, 1) + self._multi_env_pos_tensor = self._initial_pos.repeat((n_envs, 1)) + self._multi_env_lookat_tensor = self._initial_lookat.repeat((n_envs, 1)) + self._multi_env_up_tensor = self._initial_up.repeat((n_envs, 1)) + self._multi_env_transform_tensor = self._initial_transform.repeat((n_envs, 1, 1)) + + initial_quat = _T_to_quat_for_madrona(self._initial_transform.unsqueeze(0)) + self._multi_env_quat_tensor = initial_quat.repeat((n_envs, 1)) + + self._rasterizer.update_camera(self) + if self._raytracer is not None: + self._raytracer.update_camera(self) @gs.assert_built - def set_pose(self, transform=None, pos=None, lookat=None, up=None): + def set_pose(self, transform=None, pos=None, lookat=None, up=None, env_idx=None): """ Set the pose of the camera. - Note that `transform` has a higher priority than `pos`, `lookat`, and `up`. If `transform` is provided, the camera pose will be set based on the transform matrix. Otherwise, the camera pose will be set based on `pos`, `lookat`, and `up`. + Note that `transform` has a higher priority than `pos`, `lookat`, and `up`. + If `transform` is provided, the camera pose will be set based on the transform matrix. + Otherwise, the camera pose will be set based on `pos`, `lookat`, and `up`. Parameters ---------- @@ -448,86 +590,88 @@ def set_pose(self, transform=None, pos=None, lookat=None, up=None): The lookat point of the camera. up : array-like, shape (3,), optional The up vector of the camera. - + env_idx : array of indices in integers, optional + The environment indices. If not provided, the camera pose will be set for all environments. """ + # Check that all provided inputs are of the same type (either all torch.Tensor or all numpy.ndarray) + n_envs = max(self._visualizer.scene.n_envs, 1) if transform is not None: - assert transform.shape == (4, 4) - self._transform = transform - self._pos, self._lookat, self._up = gu.T_to_pos_lookat_up(transform) + transform = torch.as_tensor(transform, dtype=gs.tc_float, device=gs.device) + if transform.shape[-2:] != (4, 4): + raise ValueError(f"Transform shape {transform.shape} does not match (4, 4)") + if transform.ndim == 2: + transform = transform.expand((n_envs, 4, 4)) + else: + transform = self._multi_env_transform_tensor + if pos is not None: + pos = torch.as_tensor(pos, dtype=gs.tc_float, device=gs.device) + assert pos.shape[-1] == 3, f"Pos shape {pos.shape} does not match (n_envs, 3)" + if pos.ndim == 1: + pos = pos.expand((n_envs, 3)) else: - if pos is not None: - self._pos = pos + pos = self._multi_env_pos_tensor - if lookat is not None: - self._lookat = lookat + if lookat is not None: + lookat = torch.as_tensor(lookat, dtype=gs.tc_float, device=gs.device) + assert lookat.shape[-1] == 3, f"Lookat shape {lookat.shape} does not match (n_envs, 3)" + if lookat.ndim == 1: + lookat = lookat.expand((n_envs, 3)) + else: + lookat = self._multi_env_lookat_tensor + if up is not None: + up = torch.as_tensor(up, dtype=gs.tc_float, device=gs.device) + assert up.shape[-1] == 3, f"Up shape {up.shape} does not match (n_envs, 3)" + if up.ndim == 1: + up = up.expand((n_envs, 3)) + else: + up = self._multi_env_up_tensor + + if env_idx is None: + env_idx = torch.arange(n_envs) + + assert ( + transform is None or transform.shape[0] == env_idx.shape[0] + ), f"Transform shape {transform.shape} does not match env_idx shape {env_idx.shape}" + assert ( + pos is None or pos.shape[0] == env_idx.shape[0] + ), f"Pos shape {pos.shape} does not match env_idx shape {env_idx.shape}" + assert ( + lookat is None or lookat.shape[0] == env_idx.shape[0] + ), f"Lookat shape {lookat.shape} does not match env_idx shape {env_idx.shape}" + assert ( + up is None or up.shape[0] == env_idx.shape[0] + ), f"Up shape {up.shape} does not match env_idx shape {env_idx.shape}" + + new_transform = self._multi_env_transform_tensor[env_idx] + new_pos = self._multi_env_pos_tensor[env_idx] + new_lookat = self._multi_env_lookat_tensor[env_idx] + new_up = self._multi_env_up_tensor[env_idx] + if transform is not None: + new_transform = transform.clone() + new_pos, new_lookat, new_up = gu.T_to_pos_lookat_up(new_transform) + else: + if pos is not None: + new_pos = pos.clone() + if lookat is not None: + new_lookat = lookat.clone() if up is not None: - self._up = up + new_up = up.clone() + new_transform = gu.pos_lookat_up_to_T(new_pos, new_lookat, new_up) + + new_quat = _T_to_quat_for_madrona(new_transform) - self._transform = gu.pos_lookat_up_to_T(self._pos, self._lookat, self._up) + self._multi_env_pos_tensor[env_idx] = new_pos + self._multi_env_lookat_tensor[env_idx] = new_lookat + self._multi_env_up_tensor[env_idx] = new_up + self._multi_env_transform_tensor[env_idx] = new_transform + self._multi_env_quat_tensor[env_idx] = new_quat - if self._rasterizer is not None: - self._rasterizer.update_camera(self) + self._rasterizer.update_camera(self) if self._raytracer is not None: self._raytracer.update_camera(self) - def follow_entity(self, entity, fixed_axis=(None, None, None), smoothing=None, fix_orientation=False): - """ - Set the camera to follow a specified entity. - - Parameters - ---------- - entity : genesis.Entity - The entity to follow. - fixed_axis : (float, float, float), optional - The fixed axis for the camera's movement. For each axis, if None, the camera will move freely. If a float, the viewer will be fixed on at that value. - For example, [None, None, None] will allow the camera to move freely while following, [None, None, 0.5] will fix the viewer's z-axis at 0.5. - smoothing : float, optional - The smoothing factor for the camera's movement. If None, no smoothing will be applied. - fix_orientation : bool, optional - If True, the camera will maintain its orientation relative to the world. If False, the camera will look at the base link of the entity. - """ - self._followed_entity = entity - self._follow_fixed_axis = fixed_axis - self._follow_smoothing = smoothing - self._follow_fix_orientation = fix_orientation - - @gs.assert_built - def update_following(self): - """ - Update the camera position to follow the specified entity. - """ - - entity_pos = self._followed_entity.get_pos()[0].cpu().numpy() - if entity_pos.ndim > 1: # check for multiple envs - entity_pos = entity_pos[0] - camera_pos = np.array(self._pos) - camera_pose = np.array(self._transform) - lookat_pos = np.array(self._lookat) - - if self._follow_smoothing is not None: - # Smooth camera movement with a low-pass filter - camera_pos = self._follow_smoothing * camera_pos + (1 - self._follow_smoothing) * ( - entity_pos + self._init_pos - ) - lookat_pos = self._follow_smoothing * lookat_pos + (1 - self._follow_smoothing) * entity_pos - else: - camera_pos = entity_pos + self._init_pos - lookat_pos = entity_pos - - for i, fixed_axis in enumerate(self._follow_fixed_axis): - # Fix the camera's position along the specified axis - if fixed_axis is not None: - camera_pos[i] = fixed_axis - - if self._follow_fix_orientation: - # Keep the camera orientation fixed by overriding the lookat point - camera_pose[:3, 3] = camera_pos - self.set_pose(transform=camera_pose) - else: - self.set_pose(pos=camera_pos, lookat=lookat_pos) - @gs.assert_built def set_params(self, fov=None, aperture=None, focus_dist=None, intrinsics=None): """ @@ -567,8 +711,7 @@ def set_params(self, fov=None, aperture=None, focus_dist=None, intrinsics=None): else: self._fov = intrinsics_fov - if self._rasterizer is not None: - self._rasterizer.update_camera(self) + self._rasterizer.update_camera(self) if self._raytracer is not None: self._raytracer.update_camera(self) @@ -623,8 +766,30 @@ def stop_recording(self, save_to_filename=None, fps=60): self._recorded_imgs.clear() self._in_recording = False + def get_pos(self): + """The current position of the camera.""" + return self._multi_env_pos_tensor + + def get_lookat(self): + """The current lookat point of the camera.""" + return self._multi_env_lookat_tensor + + def get_up(self): + """The current up vector of the camera.""" + return self._multi_env_up_tensor + + def get_quat(self): + """The current quaternion of the camera.""" + return self._multi_env_quat_tensor + + def get_transform(self): + """ + The current transform matrix of the camera. + """ + return self._multi_env_transform_tensor + def _repr_brief(self): - return f"{self._repr_type()}: idx: {self._idx}, pos: {self._pos}, lookat: {self._lookat}" + return f"{self._repr_type()}: idx: {self._idx}, pos: {self.pos}, lookat: {self.lookat}" @property def is_built(self): @@ -717,22 +882,24 @@ def aspect_ratio(self): @property def pos(self): """The current position of the camera.""" - return np.array(self._pos) + return tensor_to_array(self._multi_env_pos_tensor[0]) @property def lookat(self): """The current lookat point of the camera.""" - return np.array(self._lookat) + return tensor_to_array(self._multi_env_lookat_tensor[0]) @property def up(self): """The current up vector of the camera.""" - return np.array(self._up) + return tensor_to_array(self._multi_env_up_tensor[0]) @property def transform(self): - """The current transform matrix of the camera.""" - return self._transform + """ + The current transform matrix of the camera. + """ + return tensor_to_array(self._multi_env_transform_tensor[0]) @property def extrinsics(self): diff --git a/genesis/vis/viewer.py b/genesis/vis/viewer.py index 150163f2b6..f673df0013 100644 --- a/genesis/vis/viewer.py +++ b/genesis/vis/viewer.py @@ -36,9 +36,9 @@ def __init__(self, options: "ViewerOptions", context): self._run_in_thread = options.run_in_thread self._refresh_rate = options.refresh_rate self._max_FPS = options.max_FPS - self._camera_init_pos = options.camera_pos - self._camera_init_lookat = options.camera_lookat - self._camera_up = options.camera_up + self._camera_init_pos = np.asarray(options.camera_pos, dtype=gs.np_float) + self._camera_init_lookat = np.asarray(options.camera_lookat, dtype=gs.np_float) + self._camera_up = np.asarray(options.camera_up, dtype=gs.np_float) self._camera_fov = options.camera_fov self._enable_interaction = options.enable_interaction @@ -219,19 +219,19 @@ def update_following(self): entity_pos = self._followed_entity.get_pos().cpu().numpy() if entity_pos.ndim > 1: # check for multiple envs entity_pos = entity_pos[0] - camera_pose = np.array(self._pyrender_viewer._trackball.pose) + camera_transform = np.asarray(self._pyrender_viewer._trackball.pose, copy=True) camera_pos = np.array(self._pyrender_viewer._trackball.pose[:3, 3]) if self._follow_smoothing is not None: # Smooth viewer movement with a low-pass filter camera_pos = self._follow_smoothing * camera_pos + (1 - self._follow_smoothing) * ( - entity_pos + np.array(self._camera_init_pos) + entity_pos + self._camera_init_pos ) self._follow_lookat = ( self._follow_smoothing * self._follow_lookat + (1 - self._follow_smoothing) * entity_pos ) else: - camera_pos = entity_pos + np.array(self._camera_init_pos) + camera_pos = entity_pos + self._camera_init_pos self._follow_lookat = entity_pos for i, fixed_axis in enumerate(self._follow_fixed_axis): @@ -241,8 +241,8 @@ def update_following(self): if self._follow_fix_orientation: # Keep the camera orientation fixed by overriding the lookat point - camera_pose[:3, 3] = camera_pos - self.set_camera_pose(pose=camera_pose) + camera_transform[:3, 3] = camera_pos + self.set_camera_pose(pose=camera_transform) else: self.set_camera_pose(pos=camera_pos, lookat=self._follow_lookat) diff --git a/genesis/vis/visualizer.py b/genesis/vis/visualizer.py index bbab840774..dbf12aebcb 100644 --- a/genesis/vis/visualizer.py +++ b/genesis/vis/visualizer.py @@ -1,4 +1,6 @@ import pyglet +import numpy as np +import torch import genesis as gs from genesis.repr_base import RBC @@ -24,7 +26,7 @@ class Visualizer(RBC): This abstraction layer manages viewer and renderers. """ - def __init__(self, scene, show_viewer, vis_options, viewer_options, renderer): + def __init__(self, scene, show_viewer, vis_options, viewer_options, renderer_options): self._t = -1 self._scene = scene @@ -32,6 +34,7 @@ def __init__(self, scene, show_viewer, vis_options, viewer_options, renderer): self._viewer = None self._rasterizer = None self._raytracer = None + self._batch_renderer = None self.viewer_lock = None # check if null to know if the Visualizer has been built # Rasterizer context is shared by viewer and rasterizer @@ -53,11 +56,11 @@ def __init__(self, scene, show_viewer, vis_options, viewer_options, renderer): display = pyglet.display.get_display() screen = display.get_default_screen() scale = screen.get_scale() - self._connected_to_display = True + self._has_display = True except Exception as e: if show_viewer: gs.raise_exception_from("No display detected. Use `show_viewer=False` for headless mode.", e) - self._connected_to_display = False + self._has_display = False if show_viewer: if gs.global_scene_list: @@ -88,14 +91,16 @@ def __init__(self, scene, show_viewer, vis_options, viewer_options, renderer): # Rasterizer is always needed for depth and segmentation mask rendering. self._rasterizer = Rasterizer(self._viewer, self._context) - if isinstance(renderer, gs.renderers.RayTracer): - from .raytracer import Raytracer + if isinstance(renderer_options, gs.renderers.BatchRenderer): + from .batch_renderer import BatchRenderer - self._renderer = self._raytracer = Raytracer(renderer, vis_options) + self._renderer = self._batch_renderer = BatchRenderer(self, renderer_options) + elif isinstance(renderer_options, gs.renderers.RayTracer): + from .raytracer import Raytracer - else: + self._renderer = self._raytracer = Raytracer(renderer_options, vis_options) + elif isinstance(renderer_options, gs.renderers.Rasterizer): self._renderer = self._rasterizer - self._raytracer = None self._cameras = gs.List() @@ -109,6 +114,9 @@ def destroy(self): if self._rasterizer is not None: self._rasterizer.destroy() self._rasterizer = None + if self._batch_renderer is not None: + self._batch_renderer.destroy() + self._batch_renderer = None if self._raytracer is not None: self._raytracer.destroy() self._raytracer = None @@ -125,6 +133,10 @@ def add_camera(self, res, pos, lookat, up, model, fov, aperture, focus_dist, GUI self._cameras.append(camera) return camera + def add_light(self, pos, dir, intensity, directional, castshadow, cutoff): + if self._batch_renderer is not None: + self._batch_renderer.add_light(pos, dir, intensity, directional, castshadow, cutoff) + def reset(self): self._t = -1 @@ -133,9 +145,13 @@ def reset(self): if self._raytracer is not None: self._raytracer.reset() + if self._batch_renderer is not None: + self._batch_renderer.reset() + if self.viewer_lock is not None: - for camera in self._cameras: - self._rasterizer.render_camera(camera) + if self._batch_renderer is None: + for camera in self._cameras: + self._rasterizer.render_camera(camera) if self._viewer is not None: self._viewer.update(auto_refresh=True) @@ -154,7 +170,11 @@ def build(self): self._raytracer.build(self._scene) for camera in self._cameras: - camera._build() + camera.build() + + # Batch renderer needs to be built after cameras are built + if self._batch_renderer is not None: + self._batch_renderer.build() # Make sure that the viewer is fully compiled and in a clean state self.reset() @@ -172,42 +192,47 @@ def update_visual_states(self): """ Update all visualization-only variables here. """ - if self._t < self._scene._t: - self._t = self._scene._t - - for camera in self._cameras: - if camera._attached_link is not None: - camera.move_to_attach() - - if self._scene.rigid_solver.is_active(): - self._scene.rigid_solver.update_geoms_render_T() - self._scene.rigid_solver.update_vgeoms() - - # drone propellers - for entity in self._scene.rigid_solver.entities: - if isinstance(entity, gs.engine.entities.DroneEntity): - entity.update_propeller_vgeoms() - - self._scene.rigid_solver.update_vgeoms_render_T() - - if self._scene.avatar_solver.is_active(): - self._scene.avatar_solver.update_geoms_render_T() - self._scene.avatar_solver._kernel_update_vgeoms( - vgeoms_info=self._scene.avatar_solver.vgeoms_info, - vgeoms_state=self._scene.avatar_solver.vgeoms_state, - links_state=self._scene.avatar_solver.links_state, - static_rigid_sim_config=self._scene.avatar_solver._static_rigid_sim_config, - ) - self._scene.avatar_solver.update_vgeoms_render_T() + # Early return if already updated previously + if self._t >= self.scene._t: + return - if self._scene.mpm_solver.is_active(): - self._scene.mpm_solver.update_render_fields() + for camera in self._cameras: + if camera._attached_link is not None: + camera.move_to_attach() + elif camera._followed_entity is not None: + camera.update_following() - if self._scene.sph_solver.is_active(): - self._scene.sph_solver.update_render_fields() + if self._scene.rigid_solver.is_active(): + self._scene.rigid_solver.update_geoms_render_T() + self._scene.rigid_solver.update_vgeoms() - if self._scene.pbd_solver.is_active(): - self._scene.pbd_solver.update_render_fields() + # drone propellers + for entity in self._scene.rigid_solver.entities: + if isinstance(entity, gs.engine.entities.DroneEntity): + entity.update_propeller_vgeoms() + + self._scene.rigid_solver.update_vgeoms_render_T() + + if self._scene.avatar_solver.is_active(): + self._scene.avatar_solver.update_geoms_render_T() + self._scene.avatar_solver._kernel_update_vgeoms( + vgeoms_info=self._scene.avatar_solver.vgeoms_info, + vgeoms_state=self._scene.avatar_solver.vgeoms_state, + links_state=self._scene.avatar_solver.links_state, + static_rigid_sim_config=self._scene.avatar_solver._static_rigid_sim_config, + ) + self._scene.avatar_solver.update_vgeoms_render_T() + + if self._scene.mpm_solver.is_active(): + self._scene.mpm_solver.update_render_fields() + + if self._scene.sph_solver.is_active(): + self._scene.sph_solver.update_render_fields() + + if self._scene.pbd_solver.is_active(): + self._scene.pbd_solver.update_render_fields() + + self._t = self._scene._t # ------------------------------------------------------------------------------------ # ----------------------------------- properties ------------------------------------- @@ -221,6 +246,10 @@ def viewer(self): def rasterizer(self): return self._rasterizer + @property + def batch_renderer(self): + return self._batch_renderer + @property def context(self): return self._context @@ -238,8 +267,8 @@ def scene(self): return self._scene @property - def connected_to_display(self): - return self._connected_to_display + def has_display(self): + return self._has_display @property def cameras(self): diff --git a/pyproject.toml b/pyproject.toml index cf52bc27d2..1cee065517 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -9,7 +9,7 @@ name = "genesis-world" version = "0.2.1" description = "A universal and generative physics engine" readme = "README.md" -requires-python = ">=3.10,<3.13" +requires-python = ">=3.10,<3.14" dependencies = [ "psutil", "taichi >= 1.7.2", @@ -57,12 +57,50 @@ dependencies = [ "z3-solver", # Used for loading raytracing special texture images used by LuisaRender "OpenEXR", - # Motion Planning library - # * 1.7.0: First version distributed on PyPI (no pre-compiled binaries for Windows OS). - # Fix OMPL DLL search directory. - "ompl>=1.7.0; platform_system != 'Windows'" + # Native batch renderer specifically designed for Genesis + "gs-madrona>=0.0.2; platform_system == 'Linux' and (platform_machine == 'x86_64' or platform_machine == 'AMD64')", ] +[project.optional-dependencies] +dev = [ + "black", + "pytest", + "pytest-xdist", + "pytest-forked", + "pytest-random-order", + "pytest-print", + "pytest-rerunfailures", + "syrupy", + "huggingface_hub", + "wandb", +] +docs = [ + # Note that currently sphinx 7 does not work, so we must use v6.2.1. Once fixed we can use a later version. + # See https://github.com/kivy/kivy/issues/8230 which tracks this issue. + "sphinx==6.2.1", + "sphinx-autobuild", + "pydata_sphinx_theme", + # For spelling + "sphinxcontrib.spelling", + # Type hints support + "sphinx-autodoc-typehints", + # Copy button for code snippets + "sphinx_copybutton", + # Markdown parser + "myst-parser", + "sphinx-subfigure", + "sphinxcontrib-video", + "sphinx-togglebutton", + "sphinx_design", +] +render = [ + "pybind11[global]", + "open3d", +] + +[project.scripts] +gs = "genesis._main:main" + [tool.setuptools.packages.find] where = ["."] include = ["genesis", "genesis.*"] @@ -92,7 +130,7 @@ addopts = [ "--dist=worksteal", "--random-order-bucket=global", "--random-order-seed=0", - "--max-worker-restart=0", + # "--max-worker-restart=0", "--durations=0", "--durations-min=40.0", "-m not benchmarks", @@ -106,41 +144,3 @@ markers = [ "required: marks minimal test set that must pass systematically on any environment before merging.", ] log_cli_level = "WARNING" - -[project.scripts] -gs = "genesis._main:main" - -[project.optional-dependencies] -dev = [ - "black", - "pytest", - "pytest-xdist", - "pytest-forked", - "pytest-random-order", - "pytest-print", - "pytest-rerunfailures", - "huggingface_hub", - "wandb", -] -docs = [ - # Note that currently sphinx 7 does not work, so we must use v6.2.1. See https://github.com/kivy/kivy/issues/8230 which tracks this issue. Once fixed we can use a later version - "sphinx==6.2.1", - "sphinx-autobuild", - "pydata_sphinx_theme", - # For spelling - "sphinxcontrib.spelling", - # Type hints support - "sphinx-autodoc-typehints", - # Copy button for code snippets - "sphinx_copybutton", - # Markdown parser - "myst-parser", - "sphinx-subfigure", - "sphinxcontrib-video", - "sphinx-togglebutton", - "sphinx_design", -] -render = [ - "pybind11[global]", - "open3d", -] diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-False-False-cuda].1.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-False-False-cuda].1.png new file mode 100644 index 0000000000..232f9de2d5 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-False-False-cuda].1.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-False-False-cuda].2.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-False-False-cuda].2.png new file mode 100644 index 0000000000..76a4bdb5c6 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-False-False-cuda].2.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-False-False-cuda].3.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-False-False-cuda].3.png new file mode 100644 index 0000000000..d737a57ead Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-False-False-cuda].3.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-False-False-cuda].png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-False-False-cuda].png new file mode 100644 index 0000000000..1c590f8438 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-False-False-cuda].png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-False-True-cuda].1.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-False-True-cuda].1.png new file mode 100644 index 0000000000..23e78eb5c0 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-False-True-cuda].1.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-False-True-cuda].2.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-False-True-cuda].2.png new file mode 100644 index 0000000000..5bf6682e63 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-False-True-cuda].2.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-False-True-cuda].3.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-False-True-cuda].3.png new file mode 100644 index 0000000000..29aad00643 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-False-True-cuda].3.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-False-True-cuda].png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-False-True-cuda].png new file mode 100644 index 0000000000..df38b387d0 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-False-True-cuda].png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-False-cuda].1.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-False-cuda].1.png new file mode 100644 index 0000000000..22fa9ac69f Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-False-cuda].1.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-False-cuda].10.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-False-cuda].10.png new file mode 100644 index 0000000000..7aec92e5d3 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-False-cuda].10.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-False-cuda].11.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-False-cuda].11.png new file mode 100644 index 0000000000..991f5453af Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-False-cuda].11.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-False-cuda].2.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-False-cuda].2.png new file mode 100644 index 0000000000..1c590f8438 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-False-cuda].2.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-False-cuda].3.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-False-cuda].3.png new file mode 100644 index 0000000000..232f9de2d5 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-False-cuda].3.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-False-cuda].4.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-False-cuda].4.png new file mode 100644 index 0000000000..0b6d19130f Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-False-cuda].4.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-False-cuda].5.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-False-cuda].5.png new file mode 100644 index 0000000000..6247c78088 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-False-cuda].5.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-False-cuda].6.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-False-cuda].6.png new file mode 100644 index 0000000000..49b4d39720 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-False-cuda].6.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-False-cuda].7.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-False-cuda].7.png new file mode 100644 index 0000000000..fb2abf1c49 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-False-cuda].7.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-False-cuda].8.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-False-cuda].8.png new file mode 100644 index 0000000000..76a4bdb5c6 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-False-cuda].8.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-False-cuda].9.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-False-cuda].9.png new file mode 100644 index 0000000000..d737a57ead Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-False-cuda].9.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-False-cuda].png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-False-cuda].png new file mode 100644 index 0000000000..e0d7898fe4 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-False-cuda].png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-True-cuda].1.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-True-cuda].1.png new file mode 100644 index 0000000000..2e09342301 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-True-cuda].1.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-True-cuda].10.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-True-cuda].10.png new file mode 100644 index 0000000000..af0d055691 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-True-cuda].10.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-True-cuda].11.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-True-cuda].11.png new file mode 100644 index 0000000000..e574d6d7cf Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-True-cuda].11.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-True-cuda].2.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-True-cuda].2.png new file mode 100644 index 0000000000..df38b387d0 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-True-cuda].2.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-True-cuda].3.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-True-cuda].3.png new file mode 100644 index 0000000000..23e78eb5c0 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-True-cuda].3.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-True-cuda].4.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-True-cuda].4.png new file mode 100644 index 0000000000..d1b7513f58 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-True-cuda].4.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-True-cuda].5.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-True-cuda].5.png new file mode 100644 index 0000000000..97218ac9b4 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-True-cuda].5.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-True-cuda].6.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-True-cuda].6.png new file mode 100644 index 0000000000..4bb813f48a Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-True-cuda].6.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-True-cuda].7.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-True-cuda].7.png new file mode 100644 index 0000000000..7a80fa8b9f Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-True-cuda].7.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-True-cuda].8.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-True-cuda].8.png new file mode 100644 index 0000000000..5bf6682e63 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-True-cuda].8.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-True-cuda].9.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-True-cuda].9.png new file mode 100644 index 0000000000..29aad00643 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-True-cuda].9.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-True-cuda].png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-True-cuda].png new file mode 100644 index 0000000000..ec589f2ac4 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[0-True-True-cuda].png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-False-cuda].1.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-False-cuda].1.png new file mode 100644 index 0000000000..232f9de2d5 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-False-cuda].1.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-False-cuda].10.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-False-cuda].10.png new file mode 100644 index 0000000000..503526af2e Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-False-cuda].10.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-False-cuda].11.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-False-cuda].11.png new file mode 100644 index 0000000000..1ff2a81a18 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-False-cuda].11.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-False-cuda].12.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-False-cuda].12.png new file mode 100644 index 0000000000..3339ed1bb8 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-False-cuda].12.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-False-cuda].13.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-False-cuda].13.png new file mode 100644 index 0000000000..b15c08133c Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-False-cuda].13.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-False-cuda].14.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-False-cuda].14.png new file mode 100644 index 0000000000..6f94b4ea65 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-False-cuda].14.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-False-cuda].15.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-False-cuda].15.png new file mode 100644 index 0000000000..3e162f463d Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-False-cuda].15.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-False-cuda].2.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-False-cuda].2.png new file mode 100644 index 0000000000..a7c8d74d0b Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-False-cuda].2.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-False-cuda].3.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-False-cuda].3.png new file mode 100644 index 0000000000..8d45cb0454 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-False-cuda].3.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-False-cuda].4.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-False-cuda].4.png new file mode 100644 index 0000000000..cbae960199 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-False-cuda].4.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-False-cuda].5.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-False-cuda].5.png new file mode 100644 index 0000000000..be4cd9677d Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-False-cuda].5.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-False-cuda].6.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-False-cuda].6.png new file mode 100644 index 0000000000..718bc96a3d Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-False-cuda].6.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-False-cuda].7.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-False-cuda].7.png new file mode 100644 index 0000000000..a7725d88f8 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-False-cuda].7.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-False-cuda].8.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-False-cuda].8.png new file mode 100644 index 0000000000..6dec5682f5 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-False-cuda].8.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-False-cuda].9.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-False-cuda].9.png new file mode 100644 index 0000000000..ff1286ffc5 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-False-cuda].9.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-False-cuda].png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-False-cuda].png new file mode 100644 index 0000000000..1c590f8438 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-False-cuda].png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-True-cuda].1.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-True-cuda].1.png new file mode 100644 index 0000000000..23e78eb5c0 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-True-cuda].1.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-True-cuda].10.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-True-cuda].10.png new file mode 100644 index 0000000000..aea1177e5b Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-True-cuda].10.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-True-cuda].11.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-True-cuda].11.png new file mode 100644 index 0000000000..c6c2c98578 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-True-cuda].11.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-True-cuda].12.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-True-cuda].12.png new file mode 100644 index 0000000000..82e249f0ed Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-True-cuda].12.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-True-cuda].13.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-True-cuda].13.png new file mode 100644 index 0000000000..30497c4dc0 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-True-cuda].13.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-True-cuda].14.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-True-cuda].14.png new file mode 100644 index 0000000000..2b79217ee2 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-True-cuda].14.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-True-cuda].15.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-True-cuda].15.png new file mode 100644 index 0000000000..820e662d36 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-True-cuda].15.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-True-cuda].2.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-True-cuda].2.png new file mode 100644 index 0000000000..d47296d5f1 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-True-cuda].2.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-True-cuda].3.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-True-cuda].3.png new file mode 100644 index 0000000000..f304aa8b60 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-True-cuda].3.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-True-cuda].4.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-True-cuda].4.png new file mode 100644 index 0000000000..97f3fab4a7 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-True-cuda].4.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-True-cuda].5.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-True-cuda].5.png new file mode 100644 index 0000000000..8ef334f7d0 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-True-cuda].5.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-True-cuda].6.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-True-cuda].6.png new file mode 100644 index 0000000000..4ec98c15d6 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-True-cuda].6.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-True-cuda].7.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-True-cuda].7.png new file mode 100644 index 0000000000..f9ab0d6501 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-True-cuda].7.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-True-cuda].8.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-True-cuda].8.png new file mode 100644 index 0000000000..5bf6682e63 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-True-cuda].8.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-True-cuda].9.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-True-cuda].9.png new file mode 100644 index 0000000000..29aad00643 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-True-cuda].9.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-True-cuda].png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-True-cuda].png new file mode 100644 index 0000000000..df38b387d0 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-False-True-cuda].png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].1.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].1.png new file mode 100644 index 0000000000..22fa9ac69f Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].1.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].10.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].10.png new file mode 100644 index 0000000000..a7c8d74d0b Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].10.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].11.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].11.png new file mode 100644 index 0000000000..8d45cb0454 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].11.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].12.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].12.png new file mode 100644 index 0000000000..cbae960199 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].12.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].13.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].13.png new file mode 100644 index 0000000000..be4cd9677d Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].13.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].14.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].14.png new file mode 100644 index 0000000000..718bc96a3d Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].14.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].15.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].15.png new file mode 100644 index 0000000000..a7725d88f8 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].15.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].16.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].16.png new file mode 100644 index 0000000000..0b6d19130f Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].16.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].17.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].17.png new file mode 100644 index 0000000000..6247c78088 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].17.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].18.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].18.png new file mode 100644 index 0000000000..ac430ba6ec Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].18.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].19.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].19.png new file mode 100644 index 0000000000..bd7a2f30a6 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].19.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].2.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].2.png new file mode 100644 index 0000000000..e6b06f0e15 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].2.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].20.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].20.png new file mode 100644 index 0000000000..84ebdded14 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].20.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].21.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].21.png new file mode 100644 index 0000000000..f75d40806d Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].21.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].22.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].22.png new file mode 100644 index 0000000000..66715303f0 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].22.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].23.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].23.png new file mode 100644 index 0000000000..5325e51ca9 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].23.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].24.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].24.png new file mode 100644 index 0000000000..d600deaca4 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].24.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].25.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].25.png new file mode 100644 index 0000000000..5eb4f22dd3 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].25.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].26.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].26.png new file mode 100644 index 0000000000..68d305b93e Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].26.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].27.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].27.png new file mode 100644 index 0000000000..677b122fff Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].27.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].28.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].28.png new file mode 100644 index 0000000000..303d8cdb34 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].28.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].29.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].29.png new file mode 100644 index 0000000000..b1ef9db717 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].29.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].3.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].3.png new file mode 100644 index 0000000000..388f0794cf Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].3.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].30.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].30.png new file mode 100644 index 0000000000..c0d7cf8991 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].30.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].31.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].31.png new file mode 100644 index 0000000000..df10a947af Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].31.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].32.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].32.png new file mode 100644 index 0000000000..6dec5682f5 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].32.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].33.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].33.png new file mode 100644 index 0000000000..ff1286ffc5 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].33.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].34.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].34.png new file mode 100644 index 0000000000..503526af2e Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].34.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].35.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].35.png new file mode 100644 index 0000000000..1ff2a81a18 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].35.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].36.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].36.png new file mode 100644 index 0000000000..3339ed1bb8 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].36.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].37.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].37.png new file mode 100644 index 0000000000..b15c08133c Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].37.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].38.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].38.png new file mode 100644 index 0000000000..6f94b4ea65 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].38.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].39.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].39.png new file mode 100644 index 0000000000..3e162f463d Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].39.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].4.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].4.png new file mode 100644 index 0000000000..896c91ac66 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].4.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].40.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].40.png new file mode 100644 index 0000000000..db44222c62 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].40.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].41.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].41.png new file mode 100644 index 0000000000..97a40267b5 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].41.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].42.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].42.png new file mode 100644 index 0000000000..b9344dd2a0 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].42.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].43.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].43.png new file mode 100644 index 0000000000..439247bc52 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].43.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].44.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].44.png new file mode 100644 index 0000000000..b47c5d1075 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].44.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].45.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].45.png new file mode 100644 index 0000000000..130eea0faf Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].45.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].46.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].46.png new file mode 100644 index 0000000000..b62ffcec33 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].46.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].47.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].47.png new file mode 100644 index 0000000000..41e5e9bf1e Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].47.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].5.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].5.png new file mode 100644 index 0000000000..a778ad362c Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].5.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].6.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].6.png new file mode 100644 index 0000000000..3ea6d42be7 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].6.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].7.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].7.png new file mode 100644 index 0000000000..f3b81229a4 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].7.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].8.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].8.png new file mode 100644 index 0000000000..1c590f8438 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].8.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].9.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].9.png new file mode 100644 index 0000000000..232f9de2d5 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].9.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].png new file mode 100644 index 0000000000..e0d7898fe4 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-False-cuda].png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].1.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].1.png new file mode 100644 index 0000000000..2e09342301 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].1.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].10.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].10.png new file mode 100644 index 0000000000..d47296d5f1 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].10.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].11.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].11.png new file mode 100644 index 0000000000..f304aa8b60 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].11.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].12.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].12.png new file mode 100644 index 0000000000..97f3fab4a7 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].12.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].13.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].13.png new file mode 100644 index 0000000000..8ef334f7d0 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].13.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].14.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].14.png new file mode 100644 index 0000000000..4ec98c15d6 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].14.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].15.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].15.png new file mode 100644 index 0000000000..f9ab0d6501 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].15.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].16.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].16.png new file mode 100644 index 0000000000..d1b7513f58 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].16.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].17.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].17.png new file mode 100644 index 0000000000..97218ac9b4 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].17.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].18.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].18.png new file mode 100644 index 0000000000..96b7debf0e Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].18.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].19.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].19.png new file mode 100644 index 0000000000..a18799a632 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].19.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].2.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].2.png new file mode 100644 index 0000000000..e6b89bd353 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].2.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].20.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].20.png new file mode 100644 index 0000000000..9245d559f9 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].20.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].21.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].21.png new file mode 100644 index 0000000000..63e1d76cdc Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].21.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].22.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].22.png new file mode 100644 index 0000000000..d73ec33629 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].22.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].23.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].23.png new file mode 100644 index 0000000000..1156bd1a0a Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].23.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].24.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].24.png new file mode 100644 index 0000000000..4bb813f48a Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].24.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].25.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].25.png new file mode 100644 index 0000000000..7a80fa8b9f Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].25.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].26.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].26.png new file mode 100644 index 0000000000..2f8987ecbc Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].26.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].27.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].27.png new file mode 100644 index 0000000000..f5c59ba112 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].27.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].28.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].28.png new file mode 100644 index 0000000000..ca2b31dde2 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].28.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].29.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].29.png new file mode 100644 index 0000000000..a950f946ee Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].29.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].3.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].3.png new file mode 100644 index 0000000000..0aa3646184 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].3.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].30.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].30.png new file mode 100644 index 0000000000..ad040cc0b7 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].30.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].31.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].31.png new file mode 100644 index 0000000000..e849fdf26b Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].31.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].32.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].32.png new file mode 100644 index 0000000000..5bf6682e63 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].32.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].33.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].33.png new file mode 100644 index 0000000000..29aad00643 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].33.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].34.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].34.png new file mode 100644 index 0000000000..aea1177e5b Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].34.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].35.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].35.png new file mode 100644 index 0000000000..c6c2c98578 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].35.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].36.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].36.png new file mode 100644 index 0000000000..82e249f0ed Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].36.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].37.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].37.png new file mode 100644 index 0000000000..30497c4dc0 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].37.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].38.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].38.png new file mode 100644 index 0000000000..2b79217ee2 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].38.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].39.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].39.png new file mode 100644 index 0000000000..820e662d36 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].39.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].4.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].4.png new file mode 100644 index 0000000000..f35370f52c Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].4.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].40.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].40.png new file mode 100644 index 0000000000..af0d055691 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].40.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].41.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].41.png new file mode 100644 index 0000000000..e574d6d7cf Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].41.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].42.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].42.png new file mode 100644 index 0000000000..c49f95df2a Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].42.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].43.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].43.png new file mode 100644 index 0000000000..28f56c1607 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].43.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].44.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].44.png new file mode 100644 index 0000000000..c4a2d2f41e Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].44.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].45.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].45.png new file mode 100644 index 0000000000..1bb0cccfd4 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].45.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].46.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].46.png new file mode 100644 index 0000000000..6d5a4b8f20 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].46.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].47.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].47.png new file mode 100644 index 0000000000..9b2b0e4497 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].47.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].5.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].5.png new file mode 100644 index 0000000000..0e680802ee Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].5.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].6.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].6.png new file mode 100644 index 0000000000..966f47d9bd Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].6.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].7.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].7.png new file mode 100644 index 0000000000..e0ebe62077 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].7.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].8.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].8.png new file mode 100644 index 0000000000..df38b387d0 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].8.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].9.png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].9.png new file mode 100644 index 0000000000..23e78eb5c0 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].9.png differ diff --git a/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].png b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].png new file mode 100644 index 0000000000..ec589f2ac4 Binary files /dev/null and b/tests/__snapshots__/test_render/test_madrona_batch_rendering[4-True-True-cuda].png differ diff --git a/tests/conftest.py b/tests/conftest.py index 9fc546f1a8..0725a2946b 100644 --- a/tests/conftest.py +++ b/tests/conftest.py @@ -287,6 +287,10 @@ def initialize_genesis(request, backend, taichi_offline_cache): if not taichi_offline_cache: os.environ["TI_OFFLINE_CACHE"] = "0" + try: + gs.utils.get_device(backend) + except gs.GenesisException: + pytest.skip(f"Backend '{backend}' not available on this machine") gs.init(backend=backend, precision=precision, debug=debug, seed=0, logging_level=logging_level) gs.logger.addFilter(lambda record: ALLOCATE_TENSOR_WARNING not in record.getMessage()) if backend != gs.cpu and gs.backend == gs.cpu: diff --git a/tests/test_render.py b/tests/test_render.py index 791204eb3f..198b2833e3 100644 --- a/tests/test_render.py +++ b/tests/test_render.py @@ -4,12 +4,21 @@ import numpy as np import pytest import torch +from syrupy.extensions.image import PNGImageSnapshotExtension import genesis as gs +import genesis.utils.geom as gu +from genesis.utils import set_random_seed +from genesis.utils.image_exporter import FrameImageExporter from .utils import assert_allclose, assert_array_equal +@pytest.fixture +def png_snapshot(snapshot): + return snapshot.use_extension(PNGImageSnapshotExtension) + + @pytest.mark.required @pytest.mark.parametrize("segmentation_level", ["entity", "link"]) @pytest.mark.parametrize("particle_mode", ["visual", "particle"]) @@ -85,7 +94,7 @@ def test_segmentation(segmentation_level, particle_mode): @pytest.mark.required -@pytest.mark.flaky(reruns=3, condition=(sys.platform == "darwin")) +@pytest.mark.xfail(sys.platform == "darwin", reason="'shadow_mapping_pass' causes segfault on MacOS CI.") def test_batched_offscreen_rendering(show_viewer, tol): scene = gs.Scene( vis_options=gs.options.VisOptions( @@ -240,6 +249,7 @@ def test_batched_offscreen_rendering(show_viewer, tol): @pytest.mark.required +@pytest.mark.xfail(sys.platform == "darwin", reason="'shadow_mapping_pass' causes segfault on MacOS CI.") def test_batched_mounted_camera_rendering(show_viewer, tol): scene = gs.Scene( sim_options=gs.options.SimOptions( @@ -279,11 +289,10 @@ def test_batched_mounted_camera_rendering(show_viewer, tol): cams = [scene.add_camera(GUI=show_viewer, fov=70) for _ in range(n_envs)] scene.build(n_envs=n_envs, env_spacing=env_spacing) - T = np.eye(4) - T[:3, :3] = np.array([[1, 0, 0], [0, -1, 0], [0, 0, -1]]) - T[:3, 3] = np.array([0.1, 0.0, 0.1]) - for nenv, cam in enumerate(cams): - cam.attach(robot.get_link("hand"), T, nenv) + R = np.array([[1, 0, 0], [0, -1, 0], [0, 0, -1]]) + trans = np.array([0.1, 0.0, 0.1]) + for cam in cams: + cam.attach(robot.get_link("hand"), gu.trans_R_to_T(trans, R)) target_quat = np.tile(np.array([0, 1, 0, 0]), [n_envs, 1]) # pointing downwards center = np.tile(np.array([-0.25, -0.25, 0.5]), [n_envs, 1]) @@ -381,3 +390,122 @@ def test_debug_draw(show_viewer): scene.step() rgb_array, *_ = cam.render(rgb=True, depth=False, segmentation=False, colorize_seg=False, normal=False) assert_allclose(np.std(rgb_array.reshape((-1, 3)), axis=0), 0.0, tol=gs.EPS) + + +@pytest.mark.required +@pytest.mark.parametrize("backend", [gs.cuda]) +@pytest.mark.skipif(sys.platform != "linux", reason="Madrona batch renderer only supports Linux.") +@pytest.mark.parametrize("use_rasterizer", [True, False]) +@pytest.mark.parametrize("render_all_cameras", [True, False]) +@pytest.mark.parametrize("n_envs", [0, 4]) +def test_madrona_batch_rendering(tmp_path, use_rasterizer, render_all_cameras, n_envs, show_viewer, png_snapshot): + CAM_RES = (256, 256) + + pytest.importorskip("gs_madrona", reason="Python module 'gs-madrona' not installed.") + + scene = gs.Scene( + sim_options=gs.options.SimOptions( + dt=0.02, + substeps=4, + ), + renderer=gs.options.renderers.BatchRenderer( + use_rasterizer=use_rasterizer, + ), + ) + plane = scene.add_entity( + morph=gs.morphs.Plane(), + surface=gs.surfaces.Aluminium( + ior=10.0, + ), + ) + robot = scene.add_entity( + gs.morphs.URDF( + file="urdf/go2/urdf/go2.urdf", + merge_fixed_links=False, + ), + ) + cam_0 = scene.add_camera( + res=CAM_RES, + pos=(1.5, 0.5, 1.5), + lookat=(0.0, 0.0, 0.5), + fov=45, + GUI=show_viewer, + ) + cam_1 = scene.add_camera( + res=CAM_RES, + pos=(1.5, -0.5, 1.5), + lookat=(0.0, 0.0, 0.5), + fov=45, + GUI=show_viewer, + ) + cam_2 = scene.add_camera( + res=CAM_RES, + fov=45, + GUI=show_viewer, + ) + scene.add_light( + pos=[0.0, 0.0, 1.5], + dir=[1.0, 1.0, -2.0], + directional=True, + castshadow=True, + cutoff=45.0, + intensity=0.5, + ) + scene.add_light( + pos=[4.0, -4.0, 4.0], + dir=[-1.0, 1.0, -1.0], + directional=False, + castshadow=True, + cutoff=45.0, + intensity=0.5, + ) + scene.build(n_envs=n_envs, env_spacing=(0.8, 0.8)) + + # Attach cameras + R = np.eye(3) + trans = np.array([0.1, 0.0, 0.1]) + cam_2.attach(robot.get_link("Head_upper"), gu.trans_R_to_T(trans, R)) + cam_1.follow_entity(robot) + + # Create an image exporter + exporter = FrameImageExporter(tmp_path) + + # Initialize the simulation + set_random_seed(0) + dof_bounds = scene.rigid_solver.dofs_info.limit.to_torch(gs.device) + for i in range(max(n_envs, 1)): + qpos = torch.zeros(robot.n_dofs) + qpos[:2] = torch.rand(2) - 0.5 + qpos[2] = 1.0 + qpos[3:6] = 0.5 * (torch.rand(3) - 0.5) + qpos[6:] = torch.rand(robot.n_dofs - 6) - 0.5 + robot.set_dofs_position(qpos, envs_idx=([i] if n_envs else None)) + + qvel = torch.zeros(robot.n_dofs) + qvel[:6] = torch.rand(6) - 0.5 + robot.set_dofs_velocity(qvel, envs_idx=([i] if n_envs else None)) + + # Verify that the output is correct pixel-wise over multiple simulation steps + for i in range(2): + batch_shape = (*((n_envs,) if n_envs else ()), *CAM_RES) + if render_all_cameras: + rgba, depth, _, _ = scene.render_all_cameras(rgb=True, depth=True) + + assert len(rgba) == len(depth) == len(scene.visualizer.cameras) + assert all(e.shape == (*batch_shape, 3) for e in rgba) + assert all(e.shape == (*batch_shape, 1) for e in depth) + + exporter.export_frame_all_cameras(i, rgb=rgba, depth=depth) + else: + rgba, depth, _, _ = cam_1.render(rgb=True, depth=True) + + assert rgba.shape == (*batch_shape, 3) + assert depth.shape == (*batch_shape, 1) + + exporter.export_frame_single_camera(i, cam_1.idx, rgb=rgba, depth=depth) + + scene.step() + + for image_file in sorted(tmp_path.rglob("*.png")): + with open(image_file, "rb") as f: + assert f.read() == png_snapshot diff --git a/tests/test_utils.py b/tests/test_utils.py index b3aef6c682..8e99539b2a 100644 --- a/tests/test_utils.py +++ b/tests/test_utils.py @@ -160,6 +160,38 @@ def test_utils_geom_taichi_vs_tensor_consistency(batch_shape): np.testing.assert_allclose(np_out, tc_out, atol=1e2 * gs.EPS) +@pytest.mark.parametrize("batch_shape", [(10, 40, 25), ()]) +def test_utils_geom_numpy_vs_tensor_consistency(batch_shape): + for py_func, shapes_in, shapes_out in ( + (gu.z_up_to_R, [[3], [3], [3, 3]], [[3, 3]]), + (gu.pos_lookat_up_to_T, [[3], [3], [3]], [[4, 4]]), + ): + num_inputs = len(shapes_in) + shape_args = (*shapes_in, *shapes_out) + np_args, tc_args = [], [] + for i in range(len(shape_args)): + np_arg = np.random.randn(*batch_shape, *shape_args[i]).clip(-1.0, 1.0).astype(gs.np_float) + tc_arg = torch.as_tensor(np_arg, dtype=gs.tc_float, device=gs.device) + + if i < num_inputs: + np_args.append(np_arg) + tc_args.append(tc_arg) + + np_outs = py_func(*np_args) + if not isinstance(np_outs, (list, tuple)): + np_outs = (np_outs,) + for np_out, shape_out in zip(np_outs, shapes_out): + assert np_out.shape == (*batch_shape, *shape_out) + + tc_outs = py_func(*tc_args) + if not isinstance(tc_outs, (list, tuple)): + tc_outs = (tc_outs,) + tc_outs = tuple(map(tensor_to_array, tc_outs)) + + for np_out, tc_out in zip(np_outs, tc_outs): + np.testing.assert_allclose(np_out, tc_out, atol=gs.EPS) + + @pytest.mark.parametrize("batch_shape", [(10, 40, 25), ()]) def test_utils_geom_taichi_inverse(batch_shape): import taichi as ti