From a81bad2f9a2711a2b458902cb7ec086adfc89ee5 Mon Sep 17 00:00:00 2001 From: Trinity Chung Date: Tue, 14 Oct 2025 16:40:25 +0200 Subject: [PATCH] wip add rgb camera sensor and example --- examples/sensors/camera_franka.py | 131 +++++++++++++++++++ genesis/engine/scene.py | 36 ++--- genesis/sensors/__init__.py | 1 + genesis/sensors/base_sensor.py | 3 + genesis/sensors/contact_force.py | 3 +- genesis/sensors/rgb_camera.py | 211 ++++++++++++++++++++++++++++++ genesis/sensors/sensor_manager.py | 5 +- genesis/vis/camera.py | 40 ++++-- genesis/vis/rasterizer_context.py | 53 ++++++++ genesis/vis/visualizer.py | 19 ++- 10 files changed, 471 insertions(+), 31 deletions(-) create mode 100644 examples/sensors/camera_franka.py create mode 100644 genesis/sensors/rgb_camera.py diff --git a/examples/sensors/camera_franka.py b/examples/sensors/camera_franka.py new file mode 100644 index 000000000..659aa3522 --- /dev/null +++ b/examples/sensors/camera_franka.py @@ -0,0 +1,131 @@ +import argparse +import os + +import numpy as np +from tqdm import tqdm + +import genesis as gs +from genesis.recorders.plotters import IS_MATPLOTLIB_AVAILABLE + + +def main(): + parser = argparse.ArgumentParser() + parser.add_argument("-dt", "--timestep", type=float, default=1e-2, help="Simulation time step") + parser.add_argument("-v", "--vis", action="store_true", help="Show visualization GUI", default=True) + parser.add_argument("-nv", "--no-vis", action="store_false", dest="vis", help="Disable visualization GUI") + parser.add_argument("-c", "--cpu", action="store_true", help="Use CPU instead of GPU") + parser.add_argument("-t", "--seconds", type=float, default=3, help="Number of seconds to simulate") + args = parser.parse_args() + + ########################## init ########################## + gs.init(backend=gs.cpu if args.cpu else gs.gpu) + + ########################## create a scene ########################## + scene = gs.Scene( + sim_options=gs.options.SimOptions( + dt=args.timestep, + ), + vis_options=gs.options.VisOptions( + show_world_frame=False, + ), + viewer_options=gs.options.ViewerOptions( + camera_pos=(3.5, 0.0, 2.5), + camera_lookat=(0.0, 0.0, 0.5), + camera_fov=40, + ), + profiling_options=gs.options.ProfilingOptions( + show_FPS=False, + ), + # renderer=gs.renderers.BatchRenderer(), + show_viewer=args.vis, + ) + + ########################## entities ########################## + scene.add_entity(gs.morphs.Plane()) + franka = scene.add_entity( + gs.morphs.MJCF(file="xml/franka_emika_panda/panda.xml"), + ) + end_effector = franka.get_link("hand") + motors_dof = (0, 1, 2, 3, 4, 5, 6) + + ########################## record sensor data ########################## + head_camera = scene.add_sensor( + gs.sensors.RGBCamera( + res=(360, 240), + pos=(2.0, 2.0, 1.0), + euler=(80.0, 0.0, 140.0), + # visualize + draw_debug=True, + debug_color=(0.0, 1.0, 1.0, 0.8), + ) + ) + hand_camera = scene.add_sensor( + gs.sensors.RGBCamera( + res=(128, 128), + entity_idx=franka.idx, + link_idx_local=end_effector.idx_local, + pos_offset=(0.0, 0.0, 0.15), + euler_offset=(180.0, 0.0, 0.0), + # visualize + draw_debug=True, + ) + ) + if args.vis: + if IS_MATPLOTLIB_AVAILABLE: + head_camera.start_recording( + gs.recorders.MPLImagePlot( + title="Head Camera", + # save_to_filename="camera_franka_head.mp4", + ), + ) + hand_camera.start_recording( + gs.recorders.MPLImagePlot( + title="Hand Camera", + # save_to_filename="camera_franka_hand.mp4", + ), + ) + else: + print("matplotlib not available, skipping real-time plotting.") + + ########################## build ########################## + scene.build() + + franka.set_dofs_kp( + np.array([4500.0, 4500.0, 3500.0, 3500.0, 2000.0, 2000.0, 2000.0, 100.0, 100.0]), + ) + franka.set_dofs_kv( + np.array([450.0, 450.0, 350.0, 350.0, 200.0, 200.0, 200.0, 10.0, 10.0]), + ) + franka.set_dofs_force_range( + np.array([-87.0, -87.0, -87.0, -87.0, -12.0, -12.0, -12.0, -100.0, -100.0]), + np.array([87.0, 87.0, 87.0, 87.0, 12.0, 12.0, 12.0, 100.0, 100.0]), + ) + + circle_center = np.array([0.4, 0.0, 0.5]) + circle_radius = 0.15 + rate = np.deg2rad(2.0) + + try: + steps = int(args.seconds / args.timestep) if "PYTEST_VERSION" not in os.environ else 5 + for i in tqdm(range(steps)): + scene.step() + + # control franka to move in a circle and draw the target positions + pos = circle_center + np.array([np.cos(i * rate), np.sin(i * rate), 0]) * circle_radius + qpos = franka.inverse_kinematics( + link=end_effector, + pos=pos, + quat=np.array([0.0, 1.0, 0.0, 0.0]), + ) + franka.control_dofs_position(qpos[:-2], motors_dof) + + except KeyboardInterrupt: + gs.logger.info("Simulation interrupted, exiting.") + finally: + gs.logger.info("Simulation finished.") + + scene.stop_recording() + + +if __name__ == "__main__": + main() diff --git a/genesis/engine/scene.py b/genesis/engine/scene.py index d33a30f55..9c37db929 100644 --- a/genesis/engine/scene.py +++ b/genesis/engine/scene.py @@ -633,6 +633,9 @@ def add_camera( Warning ------- + This method is deprecated and may change or be removed in a future version. This returns a gs.Camera instead of + a gs.sensors.Camera. Please use the sensors API with `Scene.add_sensor(gs.sensors.Camera(...))` instead. + When 'pinhole' is used, the `aperture` and `focal_len` parameters are ignored. Parameters @@ -685,6 +688,11 @@ def add_camera( camera : genesis.Camera The created camera object. """ + gs.logger.warning( + "`Scene.add_camera` is deprecated and will be removed in a future version." + " Please use `Scene.add_sensor(gs.sensors.Camera(...))` instead." + ) + if denoise is None: denoise = sys.platform != "darwin" return self._visualizer.add_camera( @@ -805,19 +813,20 @@ def build( with open(os.devnull, "w") as stderr, redirect_libc_stderr(stderr): self._sim.build() - # reset state - self._reset() - self._is_built = True - - with gs.logger.timer("Compiling simulation kernels..."): - self._sim.step() - self._reset() + self._init_state = self._get_state() # visualizer with gs.logger.timer("Building visualizer..."): self._visualizer.build() + # reset state + self._reset() + + with gs.logger.timer("Compiling simulation kernels..."): + self._sim.step() + self._reset() + if self.profiling_options.show_FPS: self.FPS_tracker = FPSTracker(self.n_envs, alpha=self.profiling_options.FPS_tracker_alpha) @@ -891,15 +900,12 @@ def reset(self, state: SimState | None = None, envs_idx=None): self._recorder_manager.reset(envs_idx) def _reset(self, state: SimState | None = None, *, envs_idx=None): - if self._is_built: - if state is None: - state = self._init_state - else: - assert isinstance(state, SimState), "state must be a SimState object" - self._init_state = state - self._sim.reset(state, envs_idx) + if state is None: + state = self._init_state else: - self._init_state = self._get_state() + assert isinstance(state, SimState), "state must be a SimState object" + self._init_state = state + self._sim.reset(state, envs_idx) self._t = 0 self._forward_ready = True diff --git a/genesis/sensors/__init__.py b/genesis/sensors/__init__.py index 3ac1e4f2c..9d79e3563 100644 --- a/genesis/sensors/__init__.py +++ b/genesis/sensors/__init__.py @@ -5,4 +5,5 @@ from .raycaster import DepthCameraOptions as DepthCamera from .raycaster import RaycasterOptions as Lidar from .raycaster import RaycasterOptions as Raycaster +from .rgb_camera import RGBCameraOptions as RGBCamera from .sensor_manager import SensorManager diff --git a/genesis/sensors/base_sensor.py b/genesis/sensors/base_sensor.py index 5d39f2117..cf879281a 100644 --- a/genesis/sensors/base_sensor.py +++ b/genesis/sensors/base_sensor.py @@ -357,6 +357,9 @@ class RigidSensorOptionsMixin: def validate(self, scene: "Scene"): super().validate(scene) + self.validate_rigid_link(scene) + + def validate_rigid_link(self, scene: "Scene"): if self.entity_idx < 0 or self.entity_idx >= len(scene.entities): gs.raise_exception(f"Invalid RigidEntity index {self.entity_idx}.") entity = scene.entities[self.entity_idx] diff --git a/genesis/sensors/contact_force.py b/genesis/sensors/contact_force.py index f6b28b9d1..8095c247c 100644 --- a/genesis/sensors/contact_force.py +++ b/genesis/sensors/contact_force.py @@ -7,7 +7,7 @@ import genesis as gs from genesis.engine.solvers import RigidSolver -from genesis.utils.geom import ti_inv_transform_by_quat, trans_to_T, transform_by_quat +from genesis.utils.geom import ti_inv_transform_by_quat, transform_by_quat from genesis.utils.misc import concat_with_tensor, make_tensor_field, tensor_to_array from .base_sensor import ( @@ -21,7 +21,6 @@ Sensor, SensorOptions, SharedSensorMetadata, - _to_tuple, ) from .sensor_manager import register_sensor diff --git a/genesis/sensors/rgb_camera.py b/genesis/sensors/rgb_camera.py new file mode 100644 index 000000000..353248794 --- /dev/null +++ b/genesis/sensors/rgb_camera.py @@ -0,0 +1,211 @@ +from typing import TYPE_CHECKING, Literal, Type + +import numpy as np +import torch + +import genesis as gs +import genesis.utils.geom as gu +from genesis.sensors.base_sensor import ( + RigidSensorOptionsMixin, + Sensor, + SensorOptions, + SharedSensorMetadata, + Tuple3FType, +) +from genesis.sensors.sensor_manager import register_sensor + +if TYPE_CHECKING: + from genesis.engine.scene import Scene + from genesis.ext.pyrender.mesh import Mesh + from genesis.sensors.sensor_manager import SensorManager + from genesis.utils.ring_buffer import TensorRingBuffer + from genesis.vis.rasterizer_context import RasterizerContext + + +class RGBCameraOptions(RigidSensorOptionsMixin, SensorOptions): + """ + A camera which can be used to render RGB, depth, and segmentation images. + + Warning + ------- + When 'pinhole' is used, the `aperture` and `focal_len` parameters are ignored. + + Parameters + ---------- + pos : tuple[float, float, float], optional + The position of the camera in the scene. + euler : tuple[float, float, float], optional + The orientation in degree angles of the camera in the scene. + entity_idx : int, optional + The global entity index of the RigidEntity to which the camera is attached. If provided, this will override + pos and euler (use pos_ffset and euler_offset instead), and the camera's position and orientation will be + updated relative to this entity. Defaults to -1 (not attached to any entity). + model : Literal["pinhole", "thinlens"] + Specifies the camera model. Options are 'pinhole' or 'thinlens'. + res : tuple of int, shape (2,) + The resolution of the camera, specified as a tuple (width, height). + fov : float + The vertical field of view of the camera in degrees. + aperture : float + The aperture size of the camera, controlling depth of field. + focus_dist : float | None + The focus distance of the camera. If None, it will be auto-computed using `pos` and `lookat`. + spp : int, optional + Samples per pixel. Only available when using the RayTracer renderer. Defaults to 256. + denoise : bool + Whether to denoise the camera's rendered image. Only available when using the RayTracer renderer. + Defaults to True. If OptiX denoiser is not available on your platform, consider enabling the OIDN denoiser + option when building RayTracer. + near : float + Distance from camera center to near plane in meters. + Only available when using rasterizer in Rasterizer and BatchRender renderer. Defaults to 0.05. + far : float + Distance from camera center to far plane in meters. + Only available when using rasterizer in Rasterizer and BatchRender renderer. Defaults to 100.0. + env_idx : int, optional + The index of the environment to track the camera. + debug : bool, optional + Whether to use the debug camera. It enables to create cameras that can used to monitor / debug the + simulation without being part of the "sensors". Their output is rendered by the usual simple Rasterizer + systematically, no matter if BatchRayTracer is enabled. This way, it is possible to record the + simulation with arbitrary resolution and camera pose, without interfering with what robots can perceive + from their environment. Defaults to False. + debug_color : float, optional + The rgba color of the debug pyramid. Defaults to (1.0, 1.0, 1.0, 0.5). + debug_size : float, optional + The size of the debug pyramid. Defaults to 0.2. + """ + + pos: Tuple3FType = (0.5, 2.5, 3.5) + euler: Tuple3FType = (0.0, 0.0, 0.0) + # override from RigidSensorOptionsMixin to provide default value + entity_idx: int = -1 + + model: Literal["pinhole", "thinlens"] = "pinhole" + res: tuple[int, int] = (320, 320) + pos: Tuple3FType = (0.5, 2.5, 3.5) + fov: float = 30.0 + aperture: float = 2.8 + focus_dist: float | None = None + spp: int = 256 + denoise: bool = True + near: float = 0.05 + far: float = 100.0 + env_idx: int | None = None + + debug: bool = False + debug_color: tuple[float, float, float, float] = (1.0, 1.0, 1.0, 0.5) + debug_size: float = 0.2 + + def validate_rigid_link(self, scene: "Scene"): + if self.entity_idx >= 0: + super().validate_rigid_link(scene) + + +class RGBCameraSharedMetadata(SharedSensorMetadata): + cameras: tuple["gs.RGBCamera"] = () + + +@register_sensor(RGBCameraOptions, RGBCameraSharedMetadata, tuple) +class RGBCameraSensor(Sensor): + + def __init__( + self, + sensor_options: RGBCameraOptions, + sensor_idx: int, + data_cls: Type[tuple], + sensor_manager: "SensorManager", + ): + super().__init__(sensor_options, sensor_idx, data_cls, sensor_manager) + + self._visualizer = self._manager._sim._scene._visualizer + + self._camera = self._visualizer.add_camera( + res=self._options.res, + pos=self._options.pos, + transform=gu.trans_R_to_T(np.array(self._options.pos), gu.euler_to_R(self._options.euler)), + lookat=(0.0, 0.0, 0.0), + model=self._options.model, + fov=self._options.fov, + up=(0.0, 0.0, 1.0), + aperture=self._options.aperture, + focus_dist=self._options.focus_dist, + GUI=False, + spp=self._options.spp, + denoise=self._options.denoise, + near=self._options.near, + far=self._options.far, + env_idx=self._options.env_idx, + debug=self._options.debug, + ) + + self.debug_object: "Mesh" | None = None + self.offset_T = gu.trans_quat_to_T( + np.array(self._options.pos_offset), gu.euler_to_quat(self._options.euler_offset) + ) + + def build(self): + super().build() + # _camera will be built by visualizer + + if self._visualizer.batch_renderer is None and self._manager._sim.n_envs > 1: + gs.raise_exception( + "BatchRenderer must be enabled in the Scene to use RGBCameraSensor with n_envs > 1. " + "Add `renderer=gs.renderers.BatchRenderer()` when creating the scene." + ) + + if self._options.entity_idx >= 0: + entity = self._manager._sim.rigid_solver.entities[self._options.entity_idx] + link = entity.links[self._options.link_idx_local] + self._camera.attach(link, self.offset_T) + self._shared_metadata.cameras += (self._camera,) + + def _get_return_format(self) -> tuple[int, ...]: + return (self._options.res[1], self._options.res[0], 3) + + @classmethod + def _get_cache_dtype(cls) -> torch.dtype: + return torch.uint8 + + @classmethod + def _update_shared_ground_truth_cache( + cls, shared_metadata: RGBCameraSharedMetadata, shared_ground_truth_cache: torch.Tensor + ): + tensor_idx = 0 + for cam in shared_metadata.cameras: + rgb, *_ = cam.render(rgb=True, depth=False, segmentation=False, normal=False) + rgb_flattened = rgb.flatten() + next_idx = tensor_idx + len(rgb_flattened) + shared_ground_truth_cache[:, tensor_idx:next_idx] = torch.from_numpy(rgb_flattened).to( + device=gs.device, dtype=gs.tc_float + ) + tensor_idx = next_idx + + @classmethod + def _update_shared_cache( + cls, + shared_metadata: RGBCameraSharedMetadata, + shared_ground_truth_cache: torch.Tensor, + shared_cache: torch.Tensor, + buffered_data: "TensorRingBuffer", + ): + buffered_data.append(shared_ground_truth_cache) + cls._apply_delay_to_shared_cache(shared_metadata, shared_cache, buffered_data) + + def _draw_debug(self, context: "RasterizerContext", buffer_updates: dict[str, np.ndarray]): + """ + Draw debug pyramid where the camera is. + """ + if self.debug_object is None: + base_height = 2.0 * self._options.debug_size * np.tan(np.radians(self._options.fov) / 2.0) + base_width = base_height * self._options.res[0] / self._options.res[1] + + self.debug_object = context.draw_debug_pyramid( + T=self._camera.transform, + base_width=base_width, + base_height=base_height, + height=self._options.debug_size, + color=self._options.debug_color, + ) + else: + buffer_updates.update(context.get_buffer_debug_objects([self.debug_object], [self._camera.transform])) diff --git a/genesis/sensors/sensor_manager.py b/genesis/sensors/sensor_manager.py index 0fed5af21..37ecc3c13 100644 --- a/genesis/sensors/sensor_manager.py +++ b/genesis/sensors/sensor_manager.py @@ -30,7 +30,7 @@ def __init__(self, sim): def create_sensor(self, sensor_options: "SensorOptions") -> "Sensor": sensor_options.validate(self._sim.scene) sensor_cls, metadata_cls, data_cls = SensorManager.SENSOR_TYPES_MAP[type(sensor_options)] - self._sensors_by_type.setdefault(sensor_cls, []) + self._sensors_by_type.setdefault(sensor_cls, gs.List()) if sensor_cls not in self._sensors_metadata: self._sensors_metadata[sensor_cls] = metadata_cls() sensor = sensor_cls(sensor_options, len(self._sensors_by_type[sensor_cls]), data_cls, self) @@ -124,6 +124,9 @@ def get_cloned_from_cache(self, sensor: "Sensor", is_ground_truth: bool = False) self._cloned_cache[key] = self._cache[dtype].clone() return self._cloned_cache[key][:, sensor._cache_idx : sensor._cache_idx + sensor._cache_size] + def get_sensors_of_type(self, sensor_cls: Type["Sensor"]) -> tuple["Sensor", ...]: + return tuple(self._sensors_by_type[sensor_cls]) + @property def sensors(self): return tuple([sensor for sensor_list in self._sensors_by_type.values() for sensor in sensor_list]) diff --git a/genesis/vis/camera.py b/genesis/vis/camera.py index 5e85ef160..c70a6987c 100644 --- a/genesis/vis/camera.py +++ b/genesis/vis/camera.py @@ -1,5 +1,4 @@ import inspect -import math import os import time from functools import cached_property @@ -190,12 +189,10 @@ def build(self): # Must consider the building process done before setting initial pose, otherwise it will fail self._is_built = True - self.set_pose( - transform=self._initial_transform, - pos=self._initial_pos, - lookat=self._initial_lookat, - up=self._initial_up, - ) + if self._initial_transform is not None: + self.set_pose(transform=self._initial_transform) + else: + self.set_pose(pos=self._initial_pos, lookat=self._initial_lookat, up=self._initial_up) # FIXME: For some reason, it is necessary to update the camera twice... if self._raytracer is not None: @@ -658,7 +655,7 @@ def set_pose(self, transform=None, pos=None, lookat=None, up=None, envs_idx=None if self._is_batched: for data in (transform, pos, lookat, up): if data is not None and len(data) != n_envs: - gs.raise_exception(f"Input data inconsistent with 'envs_idx'.") + gs.raise_exception("Input data inconsistent with 'envs_idx'.") # Compute redundant quantities if transform is None: @@ -686,12 +683,27 @@ def set_pose(self, transform=None, pos=None, lookat=None, up=None, envs_idx=None self._rasterizer.update_camera(self) @gs.assert_built - def start_recording(self): + def start_recording(self, rec_options: "RecorderOptions | None" = None) -> "Recorder": """ - Start recording on the camera. After recording is started, all the rgb images rendered by `camera.render()` - will be stored, and saved to a video file when `camera.stop_recording()` is called. + Automatically read and process sensor data. See specific RecorderOptions for more details. + + Data from `sensor.read()` is used. If the sensor data needs to be preprocessed before passing to the recorder, + consider using `scene.start_recording()` instead with a custom data function. + Note that start_recording() on a camera without providing rec_options is deprecated. + + Parameters + ---------- + rec_options : RecorderOptions + The options for the recording. """ - self._in_recording = True + if rec_options is None: + gs.logger.warning( + "Camera.start_recording() without rec_options is deprecated and may be removed in future release." + "Please provide RecorderOptions and to use the new sensor recording API instead." + ) + self._in_recording = True + + super().start_recording(rec_options) @gs.assert_built def pause_recording(self): @@ -699,6 +711,8 @@ def pause_recording(self): Pause recording on the camera. After recording is paused, the rgb images rendered by `camera.render()` will not be stored. Recording can be resumed by calling `camera.start_recording()` again. """ + gs.logger.warning("Camera.pause_recording() is deprecated and may be removed in future release.") + if not self._in_recording: gs.raise_exception("Recording not started.") self._in_recording = False @@ -721,6 +735,7 @@ def stop_recording(self, save_to_filename=None, fps=60): fps : int, optional The frames per second of the video file. """ + gs.logger.warning("Camera.stop_recording() is deprecated and may be removed in future release.") if not self._in_recording: gs.raise_exception("Recording not started.") @@ -829,6 +844,7 @@ def focal_len(self): """The focal length for thinlens camera. Returns -1 for pinhole camera.""" tan_half_fov = np.tan(np.deg2rad(self._fov / 2)) if self.model == "thinlens": + # TODO: How where these magic numbers derived? if self._res[0] > self._res[1]: projected_pixel_size = min(0.036 / self._res[0], 0.024 / self._res[1]) else: diff --git a/genesis/vis/rasterizer_context.py b/genesis/vis/rasterizer_context.py index 6ede33367..6dcd83fa0 100644 --- a/genesis/vis/rasterizer_context.py +++ b/genesis/vis/rasterizer_context.py @@ -895,6 +895,59 @@ def draw_debug_box(self, bounds, color=(1.0, 0.0, 0.0, 1.0), wireframe=True, wir self.add_external_node(node) return node + def draw_debug_pyramid(self, T, base_width=0.05, base_height=0.05, height=0.05, color=(1.0, 1.0, 1.0, 0.5)): + """ + Draw a debug pyramid representing a camera frustum. + + Parameters + ---------- + T: array-like, shape (4, 4), optional + The transformation matrix. + base_width: float + The width of the pyramid base. + base_height: float + The height of the pyramid base. + height: float + The height of the pyramid (distance from apex to base). + color: RGBA color tuple + """ + T = tensor_to_array(T, dtype=np.float32) + right = T[:3, 0] + up = T[:3, 1] + forward = -T[:3, 2] + + base_center = forward * height + half_width = base_width / 2 + half_height = base_height / 2 + vertices = np.array( + [ + [0, 0, 0], # apex + base_center + half_width * right + half_height * up, # top-right + base_center - half_width * right + half_height * up, # top-left + base_center - half_width * right - half_height * up, # bottom-left + base_center + half_width * right - half_height * up, # bottom-right + ] + ) + faces = np.array( + [ + # Base (2 triangles) - facing away from apex + [1, 2, 3], + [1, 3, 4], + # Sides (4 triangles from apex to base edges) + [0, 2, 1], # left side + [0, 3, 2], # back side + [0, 4, 3], # right side + [0, 1, 4], # front side + ] + ) + + mesh = trimesh.Trimesh(vertices=vertices, faces=faces, process=False) + mesh.visual.face_colors = np.tile(np.array(color) * 255, (len(faces), 1)).astype(np.uint8) + + node = pyrender.Mesh.from_trimesh(mesh, name=f"debug_pyramid_{gs.UID()}", smooth=False, is_marker=True) + self.add_external_node(node) + return node + def draw_debug_points(self, poss, colors=(1.0, 0.0, 0.0, 0.5)): poss = tensor_to_array(poss) colors = tensor_to_array(colors) diff --git a/genesis/vis/visualizer.py b/genesis/vis/visualizer.py index 8fa54cc8d..0bf8b8251 100644 --- a/genesis/vis/visualizer.py +++ b/genesis/vis/visualizer.py @@ -116,7 +116,23 @@ def destroy(self): self._renderer = None def add_camera( - self, res, pos, lookat, up, model, fov, aperture, focus_dist, GUI, spp, denoise, near, far, env_idx, debug + self, + res, + pos, + lookat, + up, + model, + fov, + aperture, + focus_dist, + GUI, + spp, + denoise, + near, + far, + env_idx, + debug, + transform=None, ): cam_idx = len([camera for camera in self._cameras if camera.debug == debug]) camera = Camera( @@ -135,6 +151,7 @@ def add_camera( denoise, near, far, + transform=transform, env_idx=env_idx, debug=debug, )