zed
ZED stereo RGB-D camera backend.
This module defines a ZED stereo RGB-D camera wrapper built on the ZED SDK Python bindings. It provides stereo image acquisition, depth and point-cloud retrieval, intrinsics access for left/right views, and runtime configuration for resolution, frame rate, and depth processing modes. The implementation exposes ZED devices through the shared stereo RGB-D camera interface for unified downstream processing.
Key functionalities include:
- ZED SDK integration through the StereoRGBDCamera interface.
- Configurable stereo resolution, frame rate, and depth mode selection.
- Left/right RGB image retrieval with consistent image conversion utilities.
- Depth, confidence, and point-cloud data access from stereo reconstruction.
- Intrinsics retrieval for selected stereo camera views.
- Device selection by serial number and optional SVO-file input support.
- class robotblockset.cameras.zed.Zed(resolution: Tuple[int, int] = (2208, 1242), fps: int = 15, depth_mode: pyzed.sl.DEPTH_MODE = pyzed.sl.DEPTH_MODE.NONE, serial_number: str | None = None, svo_filepath: str | None = None)[source]
Bases:
StereoRGBDCameraWrapper around the ZED SDK https://www.stereolabs.com/zed-2i/
It is important to note that the ZED cameras are factory calibrated and hence provide undistorted images and corresponding intrinsics matrices.
Also note that all depth values are relative to the left camera.
Initialize a ZED stereo RGB-D camera instance.
- Parameters:
resolution (CameraResolutionType, optional) – CameraResolutionType, default=RESOLUTION_2K Requested stream resolution
(width, height).fps (int, optional) – int, default=15 Target camera frame rate.
depth_mode (sl.DEPTH_MODE, optional) – sl.DEPTH_MODE, default=NONE_DEPTH_MODE Depth processing mode configured in the ZED SDK.
serial_number (str, optional) – Camera serial number used to select a specific device.
svo_filepath (str, optional) – Path to an SVO file used as the camera input source.
- Raises:
IndexError – If the camera cannot be opened after multiple attempts.
- DEPTH_MODES = (pyzed.sl.DEPTH_MODE.NEURAL, pyzed.sl.DEPTH_MODE.NONE, pyzed.sl.DEPTH_MODE.NEURAL_LIGHT, pyzed.sl.DEPTH_MODE.NEURAL_PLUS)
- RESOLUTION_2K = (2208, 1242)
- RESOLUTION_1080 = (1920, 1080)
- RESOLUTION_720 = (1280, 720)
- RESOLUTION_VGA = (672, 376)
- resolution_to_identifier_dict = {(672, 376): pyzed.sl.RESOLUTION.VGA, (1280, 720): pyzed.sl.RESOLUTION.HD720, (1920, 1080): pyzed.sl.RESOLUTION.HD1080, (2208, 1242): pyzed.sl.RESOLUTION.HD2K}
- __init__(resolution: Tuple[int, int] = (2208, 1242), fps: int = 15, depth_mode: pyzed.sl.DEPTH_MODE = pyzed.sl.DEPTH_MODE.NONE, serial_number: str | None = None, svo_filepath: str | None = None) None[source]
Initialize a ZED stereo RGB-D camera instance.
- Parameters:
resolution (CameraResolutionType, optional) – CameraResolutionType, default=RESOLUTION_2K Requested stream resolution
(width, height).fps (int, optional) – int, default=15 Target camera frame rate.
depth_mode (sl.DEPTH_MODE, optional) – sl.DEPTH_MODE, default=NONE_DEPTH_MODE Depth processing mode configured in the ZED SDK.
serial_number (str, optional) – Camera serial number used to select a specific device.
svo_filepath (str, optional) – Path to an SVO file used as the camera input source.
- Raises:
IndexError – If the camera cannot be opened after multiple attempts.
- property fps: int
The frame rate of the camera, in frames per second.
- property resolution: Tuple[int, int]
Return the configured camera resolution.
- Returns:
Resolution
(width, height)in pixels.- Return type:
CameraResolutionType
- intrinsics_matrix(view: str = 'left') ndarray[source]
Return the intrinsics matrix for a selected stereo view.
- Parameters:
view (str, optional) – str, default=StereoRGBDCamera.LEFT_RGB Requested view identifier.
- Returns:
Rectified camera intrinsics matrix with shape
(3, 3).- Return type:
CameraIntrinsicsMatrixType
- Raises:
ValueError – If
viewis not a supported stereo view.
- property pose_of_right_view_in_left_view: ndarray
Return the right-camera pose expressed in the left-camera frame.
- Returns:
Homogeneous transform from left view to right view.
- Return type:
HomogeneousMatrixType
- property depth_enabled: bool
Enable or disable depth processing.
Runtime parameter to enable/disable the depth & point_cloud computation. This speeds up the RGB image capture.
- get_colored_point_cloud() PointCloud[source]
Grab a new frame and return the corresponding colored point cloud.
- Returns:
Newly acquired colored point cloud.
- Return type:
- Raises:
RuntimeError – If depth mode is disabled or depth retrieval is turned off.
Classes
|
Wrapper around the ZED SDK https://www.stereolabs.com/zed-2i/ |