Camera#
- class genesis.vis.camera.Camera(visualizer, idx=0, model='pinhole', res=(320, 320), pos=(0.5, 2.5, 3.5), lookat=(0.5, 0.5, 0.5), up=(0.0, 0.0, 1.0), fov=30, aperture=2.8, focus_dist=None, GUI=False, spp=256, denoise=True, near=0.05, far=100.0, transform=None, env_idx=None, debug=False)[source]#
Bases:
RBCA camera which can be used to render RGB, depth, and segmentation images. Supports either rasterizer or raytracer for rendering, specified by scene.renderer.
- Parameters:
visualizer (genesis.Visualizer) – The visualizer object that the camera is associated with.
idx (int) – The index of the camera.
model (str) – 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).
pos (tuple of float, shape (3,)) – The position of the camera in the scene, specified as (x, y, z).
lookat (tuple of float, shape (3,)) – The point in the scene that the camera is looking at, specified as (x, y, z).
up (tuple of float, shape (3,)) – The up vector of the camera, defining its orientation, specified as (x, y, z).
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.
GUI (bool) – Whether to display the camera’s rendered image in a separate GUI window.
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.
transform (np.ndarray, shape (4, 4), optional) – The transform matrix of the camera.
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.
- attach(rigid_link, offset_T)[source]#
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.
- Parameters:
rigid_link (genesis.RigidLink) – 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.
- detach()[source]#
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.
- move_to_attach()[source]#
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.
- Raises:
Exception – If the camera has not been attached to a rigid link.
- follow_entity(entity, fixed_axis=(None, None, None), smoothing=None, fix_orientation=False)[source]#
Set the camera to follow a specified rigid 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.
- unfollow_entity()[source]#
Stop following any rigid entity with the camera.
Calling this method has no effect if the camera is not currently following any entity.
- render(rgb=True, depth=False, segmentation=False, colorize_seg=False, normal=False, antialiasing=False, force_render=False)[source]#
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].
Note
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:
rgb (bool, optional) – Whether to render RGB image(s).
depth (bool, optional) – Whether to render depth image(s).
segmentation (bool, optional) – Whether to render the segmentation mask(s).
colorize_seg (bool, optional) – If True, the segmentation mask will be colorized.
normal (bool, optional) – Whether to render the surface normal.
antialiasing (bool, optional) – Whether to apply anti-aliasing. Only supported by ‘BatchRenderer’ for now.
force_render (bool, optional) – Whether to force rendering even if the scene has not changed.
- Returns:
rgb_arr (np.ndarray) – The rendered RGB image(s).
depth_arr (np.ndarray) – The rendered depth image(s).
seg_arr (np.ndarray) – The rendered segmentation mask(s).
normal_arr (np.ndarray) – The rendered surface normal(s).
- render_pointcloud(world_frame=True)[source]#
Render a partial point cloud from the camera view.
- Parameters:
world_frame (bool, optional) – Whether the point cloud is on camera frame or world frame.
- Returns:
pc (np.ndarray) – Numpy array of shape (res[0], res[1], 3) or (N, res[0], res[1], 3). Represents the point cloud in each pixel.
mask_arr (np.ndarray) – The valid depth mask. boolean array of same shape as depth_arr
- set_pose(transform=None, pos=None, lookat=None, up=None, envs_idx=None)[source]#
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.
- Parameters:
transform (np.ndarray, shape (4, 4) or (N, 4, 4), optional) – The transform matrix of the camera.
pos (array-like, shape (3,) or (N, 3), optional) – The position of the camera.
lookat (array-like, shape (3,) or (N, 3), optional) – The lookat point of the camera.
up (array-like, shape (3,) or (N, 3), optional) – The up vector of the camera.
envs_idx (array of indices in integers, optional) – The environment indices for which to update the pose. If not provided, the camera pose will be set for the specific environment bound to the camera if any, all the environments otherwise.
- start_recording()[source]#
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.
- pause_recording()[source]#
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.
- stop_recording(save_to_filename=None, fps=60)[source]#
Stop recording on the camera. Once this is called, all the rgb images stored so far will be saved to a video file. If save_to_filename is None, the video file will be saved with the name ‘{caller_file_name}_cam_{camera.idx}.mp4’.
If env_separate_rigid in VisOptions is set to True, each environment will record and save a video separately. The filenames will be identified by the indices of the environments.
- Parameters:
save_to_filename (str, optional) – Name of the output video file. If not provided, the name will be default to the name of the caller file, with camera idx, a timestamp and ‘.mp4’ extension.
fps (int, optional) – The frames per second of the video file.
- property is_built#
Whether the camera is built.
- property idx#
The global integer index of the camera.
- property uid#
The unique ID of the camera
- property model#
pinhole or thinlens.
- Type:
The camera model
- property res#
The resolution of the camera.
- property fov#
The field of view of the camera.
- property aperture#
The aperture of the camera.
- property focal_len#
The focal length for thinlens camera. Returns -1 for pinhole camera.
- property focus_dist#
The focus distance of the camera.
- property GUI#
Whether the camera will display the rendered images in a separate window.
- property spp#
Samples per pixel of the camera.
- property denoise#
Whether the camera will denoise the rendered image in raytracer.
- property near#
The near plane of the camera.
- property far#
The far plane of the camera.
- property aspect_ratio#
The aspect ratio of the camera.
- property env_idx#
Index of the environment bound to the camera, if any.
- property debug#
Whether the camera is a debug camera.
- property pos#
The current position of the camera for the tracked environment.
- property lookat#
The current lookat point of the camera for the tracked environment.
- property up#
The current up vector of the camera for the tracked environment.
- property transform#
The current transform matrix of the camera for the tracked environment.
- property extrinsics#
The current extrinsics matrix of the camera.
- property intrinsics#
The current intrinsics matrix of the camera.
- property projection_matrix#
Return the projection matrix for this camera.
- property f#
- property cx#
- property cy#