From 7f48e2575c53da11af4b09a18ec57da1c6394b51 Mon Sep 17 00:00:00 2001 From: Mathieu De Coster Date: Tue, 10 Dec 2024 14:08:03 +0100 Subject: [PATCH 1/6] Zed2i -> Zed rename, keep Zed2i and zed2i module for backwards compatibility --- .../airo_camera_toolkit/cameras/zed/zed.py | 324 ++++++++++++++++++ .../airo_camera_toolkit/cameras/zed/zed2i.py | 319 +---------------- 2 files changed, 328 insertions(+), 315 deletions(-) create mode 100644 airo-camera-toolkit/airo_camera_toolkit/cameras/zed/zed.py diff --git a/airo-camera-toolkit/airo_camera_toolkit/cameras/zed/zed.py b/airo-camera-toolkit/airo_camera_toolkit/cameras/zed/zed.py new file mode 100644 index 0000000..9148d08 --- /dev/null +++ b/airo-camera-toolkit/airo_camera_toolkit/cameras/zed/zed.py @@ -0,0 +1,324 @@ +from __future__ import annotations + +from typing import Any, List, Optional + +from loguru import logger + +try: + import pyzed.sl as sl + +except ImportError: + raise ImportError( + "You should install the ZED SDK and pip install the python bindings in your environment first, see the installation README." + ) + +# check SDK version +try: + version = sl.Camera().get_sdk_version() + assert version.split(".")[0] == "4" +except AssertionError: + raise ImportError("You should install version 4.X of the SDK!") + +import time + +import cv2 +import numpy as np +from airo_camera_toolkit.interfaces import StereoRGBDCamera +from airo_camera_toolkit.utils.image_converter import ImageConverter +from airo_typing import ( + CameraIntrinsicsMatrixType, + CameraResolutionType, + HomogeneousMatrixType, + NumpyDepthMapType, + NumpyFloatImageType, + NumpyIntImageType, + OpenCVIntImageType, + PointCloud, +) + + +class Zed(StereoRGBDCamera): + """ + Wrapper 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. + """ + + # for more info on the different depth modes, see: + # https://www.stereolabs.com/docs/api/group__Depth__group.html#ga391147e2eab8e101a7ff3a06cbed22da + # keep in mind though that the depth map is calculated during the `grab`operation, so the depth mode also influences the + # fps of the rgb images, which is why the default depth mode is None + + NEURAL_DEPTH_MODE = sl.DEPTH_MODE.NEURAL + + # no depth mode, higher troughput of the RGB images as the GPU has to do less work + # can also turn depth off in the runtime params, which is recommended as it allows for switching at runtime. + NONE_DEPTH_MODE = sl.DEPTH_MODE.NONE + PERFORMANCE_DEPTH_MODE = sl.DEPTH_MODE.PERFORMANCE + QUALITY_DEPTH_MODE = sl.DEPTH_MODE.QUALITY + ULTRA_DEPTH_MODE = sl.DEPTH_MODE.ULTRA + DEPTH_MODES = (NEURAL_DEPTH_MODE, NONE_DEPTH_MODE, PERFORMANCE_DEPTH_MODE, QUALITY_DEPTH_MODE, ULTRA_DEPTH_MODE) + + # for info on image resolution, pixel sizes, fov..., see: + # https://support.stereolabs.com/hc/en-us/articles/360007395634-What-is-the-camera-focal-length-and-field-of-view- + # make sure to check the combination of frame rates and resolution is available. + RESOLUTION_2K = (2208, 1242) + RESOLUTION_1080 = (1920, 1080) + RESOLUTION_720 = (1280, 720) + RESOLUTION_VGA = (672, 376) + + resolution_to_identifier_dict = { + RESOLUTION_2K: sl.RESOLUTION.HD2K, + RESOLUTION_1080: sl.RESOLUTION.HD1080, + RESOLUTION_720: sl.RESOLUTION.HD720, + RESOLUTION_VGA: sl.RESOLUTION.VGA, + } + + def __init__( # type: ignore[no-any-unimported] + self, + resolution: CameraResolutionType = RESOLUTION_2K, + fps: int = 15, + depth_mode: sl.DEPTH_MODE = NONE_DEPTH_MODE, + serial_number: Optional[str] = None, + svo_filepath: Optional[str] = None, + ) -> None: + self._resolution = resolution + self.fps = fps + self.depth_mode = depth_mode + self.serial_number = serial_number + + self.camera = sl.Camera() + + # TODO: create a configuration class for the camera parameters + self.camera_params = sl.InitParameters() + + if serial_number: + self.camera_params.set_from_serial_number(int(serial_number)) + + if svo_filepath: + input_type = sl.InputType() + input_type.set_from_svo_file(svo_filepath) + self.camera_params = sl.InitParameters(input_t=input_type, svo_real_time_mode=False) + + self.camera_params.camera_resolution = Zed2i.resolution_to_identifier_dict[resolution] + self.camera_params.camera_fps = fps + # https://www.stereolabs.com/docs/depth-sensing/depth-settings/ + self.camera_params.depth_mode = depth_mode + self.camera_params.coordinate_units = sl.UNIT.METER + # objects closerby will have artifacts so they are filtered out (querying them will give a - Infinty) + self.camera_params.depth_minimum_distance = 0.3 + self.camera_params.depth_maximum_distance = 10.0 # filter out far away objects + + if self.camera.is_opened(): + # close to open with correct params + self.camera.close() + + N_OPEN_ATTEMPTS = 5 + for i in range(N_OPEN_ATTEMPTS): + status = self.camera.open(self.camera_params) + if status == sl.ERROR_CODE.SUCCESS: + break + logger.info(f"Opening Zed2i camera failed, attempt {i + 1}/{N_OPEN_ATTEMPTS}") + if self.serial_number: + logger.info(f"Rebooting {self.serial_number}") + sl.Camera.reboot(self.serial_number) + time.sleep(2) + logger.info(f"Available ZED cameras: {sl.Camera.get_device_list()}") + self.camera = sl.Camera() + + if status != sl.ERROR_CODE.SUCCESS: + raise IndexError(f"Could not open Zed2i camera, error = {status}") + + # TODO: create a configuration class for the runtime parameters + self.runtime_params = sl.RuntimeParameters() + # Enabling fill mode changed for SDK 4.0: https://www.stereolabs.com/developers/release/4.0/migration-guide/ + self.runtime_params.enable_fill_mode = False # standard > fill for accuracy. See docs. + self.runtime_params.texture_confidence_threshold = 100 + self.runtime_params.confidence_threshold = 100 + self.depth_enabled = True + + # Enable Positional tracking (mandatory for object detection) + # positional_tracking_parameters = sl.PositionalTrackingParameters() + # If the camera is static, uncomment the following line to have better performances and boxes sticked to the ground. + # positional_tracking_parameters.set_as_static = True + # self.camera.enable_positional_tracking(positional_tracking_parameters) + + # create reusable memory blocks for the measures + # these will be allocated the first time they are used + self.image_matrix = sl.Mat() + self.image_matrix_right = sl.Mat() + self.depth_image_matrix = sl.Mat() + self.depth_matrix = sl.Mat() + self.point_cloud_matrix = sl.Mat() + + self.confidence_matrix = sl.Mat() + self.confidence_map = None + + @property + def resolution(self) -> CameraResolutionType: + return self._resolution + + def intrinsics_matrix(self, view: str = StereoRGBDCamera.LEFT_RGB) -> CameraIntrinsicsMatrixType: + # get the 'rectified' intrinsics matrices. + # https://www.stereolabs.com/docs/api/python/classpyzed_1_1sl_1_1CameraParameters.html + if view == self.LEFT_RGB: + fx = self.camera.get_camera_information().camera_configuration.calibration_parameters.left_cam.fx + fy = self.camera.get_camera_information().camera_configuration.calibration_parameters.left_cam.fy + cx = self.camera.get_camera_information().camera_configuration.calibration_parameters.left_cam.cx + cy = self.camera.get_camera_information().camera_configuration.calibration_parameters.left_cam.cy + elif view == self.RIGHT_RGB: + fx = self.camera.get_camera_information().camera_configuration.calibration_parameters.right_cam.fx + fy = self.camera.get_camera_information().camera_configuration.calibration_parameters.right_cam.fy + cx = self.camera.get_camera_information().camera_configuration.calibration_parameters.right_cam.cx + cy = self.camera.get_camera_information().camera_configuration.calibration_parameters.right_cam.cy + else: + raise ValueError(f"view must be one of {self._VIEWS}") + cam_matrix = np.zeros((3, 3)) + cam_matrix[0, 0] = fx + cam_matrix[1, 1] = fy + cam_matrix[2, 2] = 1 + cam_matrix[0, 2] = cx + cam_matrix[1, 2] = cy + return cam_matrix + + @property + def pose_of_right_view_in_left_view(self) -> HomogeneousMatrixType: + # get the 'rectified' pose of the right view wrt to the left view + # should be approx a translation along the x-axis of 120mm (Zed2i camera), expressed in the unit of the coordinates, which we set to meters. + # https://www.stereolabs.com/docs/api/python/classpyzed_1_1sl_1_1CalibrationParameters.html + # Note: the CalibrationParameters class changed for the SDK 4.0, the old .T attribute we used was removed. + return self.camera.get_camera_information().camera_configuration.calibration_parameters.stereo_transform.m + + @property + def depth_enabled(self) -> bool: + """Runtime parameter to enable/disable the depth & point_cloud computation. This speeds up the RGB image capture.""" + return self.runtime_params.enable_depth + + @depth_enabled.setter + def depth_enabled(self, value: bool) -> None: + self.runtime_params.enable_depth = value + + def _grab_images(self) -> None: + """grabs (and waits for) the latest image(s) from the camera, rectifies them and computes the depth information (based on the depth mode setting)""" + # this is a blocking call + # https://www.stereolabs.com/docs/api/python/classpyzed_1_1sl_1_1Camera.html#a2338c15f49b5f132df373a06bd281822 + # we might want to consider running this in a seperate thread and using a queue to store the images? + error_code = self.camera.grab(self.runtime_params) + if error_code != sl.ERROR_CODE.SUCCESS: + raise IndexError("Could not grab new camera frame") + + def _retrieve_rgb_image(self, view: str = StereoRGBDCamera.LEFT_RGB) -> NumpyFloatImageType: + image = self._retrieve_rgb_image_as_int(view) + # convert from int to float image + # this can take up ~ ms for larger images (can impact FPS) + image = ImageConverter.from_numpy_int_format(image).image_in_numpy_format + return image + + def _retrieve_rgb_image_as_int(self, view: str = StereoRGBDCamera.LEFT_RGB) -> NumpyIntImageType: + assert view in StereoRGBDCamera._VIEWS + image_bgra: OpenCVIntImageType + if view == StereoRGBDCamera.RIGHT_RGB: + self.camera.retrieve_image(self.image_matrix_right, sl.VIEW.RIGHT) + image_bgra = self.image_matrix_right.get_data() + else: + self.camera.retrieve_image(self.image_matrix, sl.VIEW.LEFT) + image_bgra = self.image_matrix.get_data() + + image = cv2.cvtColor(image_bgra, cv2.COLOR_BGRA2RGB) + return image + + def _retrieve_depth_map(self) -> NumpyDepthMapType: + assert self.depth_mode != self.NONE_DEPTH_MODE, "Cannot retrieve depth data if depth mode is NONE" + assert self.depth_enabled, "Cannot retrieve depth data if depth is disabled" + self.camera.retrieve_measure(self.depth_matrix, sl.MEASURE.DEPTH) + depth_map = self.depth_matrix.get_data() + return depth_map + + def _retrieve_depth_image(self) -> NumpyIntImageType: + assert self.depth_mode != self.NONE_DEPTH_MODE, "Cannot retrieve depth data if depth mode is NONE" + assert self.depth_enabled, "Cannot retrieve depth data if depth is disabled" + self.camera.retrieve_image(self.depth_image_matrix, sl.VIEW.DEPTH) + image_bgra = self.depth_image_matrix.get_data() + # image = image[..., :3] + image = cv2.cvtColor(image_bgra, cv2.COLOR_BGRA2RGB) + return image + + def _retrieve_colored_point_cloud(self) -> PointCloud: + assert self.depth_mode != self.NONE_DEPTH_MODE, "Cannot retrieve depth data if depth mode is NONE" + assert self.depth_enabled, "Cannot retrieve depth data if depth is disabled" + self.camera.retrieve_measure(self.point_cloud_matrix, sl.MEASURE.XYZ) + # shape (width, height, 4) with the 4th dim being x,y,z,(rgba packed into float) + # can be nan,nan,nan, nan (no point in the point_cloud on this pixel) + # or x,y,z, nan (no color information on this pixel??) + # or x,y,z, value (color information on this pixel) + + point_cloud_XYZ_ = self.point_cloud_matrix.get_data() + + positions = cv2.cvtColor(point_cloud_XYZ_, cv2.COLOR_BGRA2BGR).reshape(-1, 3) + colors = self._retrieve_rgb_image_as_int().reshape(-1, 3) + + return PointCloud(positions, colors) + + def _retrieve_confidence_map(self) -> NumpyFloatImageType: + self.camera.retrieve_measure(self.confidence_matrix, sl.MEASURE.CONFIDENCE) + return self.confidence_matrix.get_data() # single channel float32 image + + def get_colored_point_cloud(self) -> PointCloud: + assert self.depth_mode != self.NONE_DEPTH_MODE, "Cannot retrieve depth data if depth mode is NONE" + assert self.depth_enabled, "Cannot retrieve depth data if depth is disabled" + + self._grab_images() + return self._retrieve_colored_point_cloud() + + @staticmethod + def list_camera_serial_numbers() -> List[str]: + """ + List all connected ZED cameras + can be used to select a device ID or to check if cameras are connected. + """ + device_list = sl.Camera.get_device_list() + return device_list + + # manage resources + # this is important if you want to reuse the camera + # multiple times within a python script, in which case you should release the camera before creating a new object. + # cf. https://stackoverflow.com/questions/865115/how-do-i-correctly-clean-up-a-python-object + def __enter__(self) -> StereoRGBDCamera: + return self + + def __exit__(self, exc_type: Any, exc_value: Any, traceback: Any) -> None: + self.camera.close() + + +class Zed2i(Zed): + """Present for backwards compatibility, use Zed instead.""" + + +def _test_zed_implementation(): + """this script serves as a 'test' for the zed implementation.""" + from airo_camera_toolkit.cameras.manual_test_hw import manual_test_stereo_rgbd_camera, profile_rgb_throughput + + # zed specific tests: + # - list all serial numbers of the cameras + serial_numbers = Zed.list_camera_serial_numbers() + print(serial_numbers) + input("each camera connected to the pc should be listed, press enter to continue") + + # test rgbd stereo camera + + with Zed(Zed.RESOLUTION_2K, fps=15, depth_mode=Zed.PERFORMANCE_DEPTH_MODE) as zed: + print(zed.get_colored_point_cloud().points) # TODO: test the point_cloud more explicity? + manual_test_stereo_rgbd_camera(zed) + + # profile rgb throughput, should be at 60FPS, i.e. 0.017s + + zed = Zed(Zed.RESOLUTION_720, fps=60) + profile_rgb_throughput(zed) + + +if __name__ == "__main__": + _test_zed_implementation() diff --git a/airo-camera-toolkit/airo_camera_toolkit/cameras/zed/zed2i.py b/airo-camera-toolkit/airo_camera_toolkit/cameras/zed/zed2i.py index 34695f2..2d31ed0 100644 --- a/airo-camera-toolkit/airo_camera_toolkit/cameras/zed/zed2i.py +++ b/airo-camera-toolkit/airo_camera_toolkit/cameras/zed/zed2i.py @@ -1,317 +1,6 @@ -from __future__ import annotations - -from typing import Any, List, Optional - -from loguru import logger - -try: - import pyzed.sl as sl - -except ImportError: - raise ImportError( - "You should install the ZED SDK and pip install the python bindings in your environment first, see the installation README." - ) - -# check SDK version -try: - version = sl.Camera().get_sdk_version() - assert version.split(".")[0] == "4" -except AssertionError: - raise ImportError("You should install version 4.X of the SDK!") - - -import time - -import cv2 -import numpy as np -from airo_camera_toolkit.interfaces import StereoRGBDCamera -from airo_camera_toolkit.utils.image_converter import ImageConverter -from airo_typing import ( - CameraIntrinsicsMatrixType, - CameraResolutionType, - HomogeneousMatrixType, - NumpyDepthMapType, - NumpyFloatImageType, - NumpyIntImageType, - OpenCVIntImageType, - PointCloud, -) - - -class Zed2i(StereoRGBDCamera): - """ - Wrapper around the ZED2i 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. - """ - - # for more info on the different depth modes, see: - # https://www.stereolabs.com/docs/api/group__Depth__group.html#ga391147e2eab8e101a7ff3a06cbed22da - # keep in mind though that the depth map is calculated during the `grab`operation, so the depth mode also influences the - # fps of the rgb images, which is why the default depth mode is None - - NEURAL_DEPTH_MODE = sl.DEPTH_MODE.NEURAL - - # no depth mode, higher troughput of the RGB images as the GPU has to do less work - # can also turn depth off in the runtime params, which is recommended as it allows for switching at runtime. - NONE_DEPTH_MODE = sl.DEPTH_MODE.NONE - PERFORMANCE_DEPTH_MODE = sl.DEPTH_MODE.PERFORMANCE - QUALITY_DEPTH_MODE = sl.DEPTH_MODE.QUALITY - ULTRA_DEPTH_MODE = sl.DEPTH_MODE.ULTRA - DEPTH_MODES = (NEURAL_DEPTH_MODE, NONE_DEPTH_MODE, PERFORMANCE_DEPTH_MODE, QUALITY_DEPTH_MODE, ULTRA_DEPTH_MODE) - - # for info on image resolution, pixel sizes, fov..., see: - # https://support.stereolabs.com/hc/en-us/articles/360007395634-What-is-the-camera-focal-length-and-field-of-view- - # make sure to check the combination of frame rates and resolution is available. - RESOLUTION_2K = (2208, 1242) - RESOLUTION_1080 = (1920, 1080) - RESOLUTION_720 = (1280, 720) - RESOLUTION_VGA = (672, 376) - - resolution_to_identifier_dict = { - RESOLUTION_2K: sl.RESOLUTION.HD2K, - RESOLUTION_1080: sl.RESOLUTION.HD1080, - RESOLUTION_720: sl.RESOLUTION.HD720, - RESOLUTION_VGA: sl.RESOLUTION.VGA, - } - - def __init__( # type: ignore[no-any-unimported] - self, - resolution: CameraResolutionType = RESOLUTION_2K, - fps: int = 15, - depth_mode: sl.DEPTH_MODE = NONE_DEPTH_MODE, - serial_number: Optional[str] = None, - svo_filepath: Optional[str] = None, - ) -> None: - self._resolution = resolution - self.fps = fps - self.depth_mode = depth_mode - self.serial_number = serial_number - - self.camera = sl.Camera() - - # TODO: create a configuration class for the camera parameters - self.camera_params = sl.InitParameters() - - if serial_number: - self.camera_params.set_from_serial_number(int(serial_number)) - - if svo_filepath: - input_type = sl.InputType() - input_type.set_from_svo_file(svo_filepath) - self.camera_params = sl.InitParameters(input_t=input_type, svo_real_time_mode=False) - - self.camera_params.camera_resolution = Zed2i.resolution_to_identifier_dict[resolution] - self.camera_params.camera_fps = fps - # https://www.stereolabs.com/docs/depth-sensing/depth-settings/ - self.camera_params.depth_mode = depth_mode - self.camera_params.coordinate_units = sl.UNIT.METER - # objects closerby will have artifacts so they are filtered out (querying them will give a - Infinty) - self.camera_params.depth_minimum_distance = 0.3 - self.camera_params.depth_maximum_distance = 10.0 # filter out far away objects - - if self.camera.is_opened(): - # close to open with correct params - self.camera.close() - - N_OPEN_ATTEMPTS = 5 - for i in range(N_OPEN_ATTEMPTS): - status = self.camera.open(self.camera_params) - if status == sl.ERROR_CODE.SUCCESS: - break - logger.info(f"Opening Zed2i camera failed, attempt {i + 1}/{N_OPEN_ATTEMPTS}") - if self.serial_number: - logger.info(f"Rebooting {self.serial_number}") - sl.Camera.reboot(self.serial_number) - time.sleep(2) - logger.info(f"Available ZED cameras: {sl.Camera.get_device_list()}") - self.camera = sl.Camera() - - if status != sl.ERROR_CODE.SUCCESS: - raise IndexError(f"Could not open Zed2i camera, error = {status}") - - # TODO: create a configuration class for the runtime parameters - self.runtime_params = sl.RuntimeParameters() - # Enabling fill mode changed for SDK 4.0: https://www.stereolabs.com/developers/release/4.0/migration-guide/ - self.runtime_params.enable_fill_mode = False # standard > fill for accuracy. See docs. - self.runtime_params.texture_confidence_threshold = 100 - self.runtime_params.confidence_threshold = 100 - self.depth_enabled = True - - # Enable Positional tracking (mandatory for object detection) - # positional_tracking_parameters = sl.PositionalTrackingParameters() - # If the camera is static, uncomment the following line to have better performances and boxes sticked to the ground. - # positional_tracking_parameters.set_as_static = True - # self.camera.enable_positional_tracking(positional_tracking_parameters) - - # create reusable memory blocks for the measures - # these will be allocated the first time they are used - self.image_matrix = sl.Mat() - self.image_matrix_right = sl.Mat() - self.depth_image_matrix = sl.Mat() - self.depth_matrix = sl.Mat() - self.point_cloud_matrix = sl.Mat() - - self.confidence_matrix = sl.Mat() - self.confidence_map = None - - @property - def resolution(self) -> CameraResolutionType: - return self._resolution - - def intrinsics_matrix(self, view: str = StereoRGBDCamera.LEFT_RGB) -> CameraIntrinsicsMatrixType: - # get the 'rectified' intrinsics matrices. - # https://www.stereolabs.com/docs/api/python/classpyzed_1_1sl_1_1CameraParameters.html - if view == self.LEFT_RGB: - fx = self.camera.get_camera_information().camera_configuration.calibration_parameters.left_cam.fx - fy = self.camera.get_camera_information().camera_configuration.calibration_parameters.left_cam.fy - cx = self.camera.get_camera_information().camera_configuration.calibration_parameters.left_cam.cx - cy = self.camera.get_camera_information().camera_configuration.calibration_parameters.left_cam.cy - elif view == self.RIGHT_RGB: - fx = self.camera.get_camera_information().camera_configuration.calibration_parameters.right_cam.fx - fy = self.camera.get_camera_information().camera_configuration.calibration_parameters.right_cam.fy - cx = self.camera.get_camera_information().camera_configuration.calibration_parameters.right_cam.cx - cy = self.camera.get_camera_information().camera_configuration.calibration_parameters.right_cam.cy - else: - raise ValueError(f"view must be one of {self._VIEWS}") - cam_matrix = np.zeros((3, 3)) - cam_matrix[0, 0] = fx - cam_matrix[1, 1] = fy - cam_matrix[2, 2] = 1 - cam_matrix[0, 2] = cx - cam_matrix[1, 2] = cy - return cam_matrix - - @property - def pose_of_right_view_in_left_view(self) -> HomogeneousMatrixType: - # get the 'rectified' pose of the right view wrt to the left view - # should be approx a translation along the x-axis of 120mm (Zed2i camera), expressed in the unit of the coordinates, which we set to meters. - # https://www.stereolabs.com/docs/api/python/classpyzed_1_1sl_1_1CalibrationParameters.html - # Note: the CalibrationParameters class changed for the SDK 4.0, the old .T attribute we used was removed. - return self.camera.get_camera_information().camera_configuration.calibration_parameters.stereo_transform.m - - @property - def depth_enabled(self) -> bool: - """Runtime parameter to enable/disable the depth & point_cloud computation. This speeds up the RGB image capture.""" - return self.runtime_params.enable_depth - - @depth_enabled.setter - def depth_enabled(self, value: bool) -> None: - self.runtime_params.enable_depth = value - - def _grab_images(self) -> None: - """grabs (and waits for) the latest image(s) from the camera, rectifies them and computes the depth information (based on the depth mode setting)""" - # this is a blocking call - # https://www.stereolabs.com/docs/api/python/classpyzed_1_1sl_1_1Camera.html#a2338c15f49b5f132df373a06bd281822 - # we might want to consider running this in a seperate thread and using a queue to store the images? - error_code = self.camera.grab(self.runtime_params) - if error_code != sl.ERROR_CODE.SUCCESS: - raise IndexError("Could not grab new camera frame") - - def _retrieve_rgb_image(self, view: str = StereoRGBDCamera.LEFT_RGB) -> NumpyFloatImageType: - image = self._retrieve_rgb_image_as_int(view) - # convert from int to float image - # this can take up ~ ms for larger images (can impact FPS) - image = ImageConverter.from_numpy_int_format(image).image_in_numpy_format - return image - - def _retrieve_rgb_image_as_int(self, view: str = StereoRGBDCamera.LEFT_RGB) -> NumpyIntImageType: - assert view in StereoRGBDCamera._VIEWS - image_bgra: OpenCVIntImageType - if view == StereoRGBDCamera.RIGHT_RGB: - self.camera.retrieve_image(self.image_matrix_right, sl.VIEW.RIGHT) - image_bgra = self.image_matrix_right.get_data() - else: - self.camera.retrieve_image(self.image_matrix, sl.VIEW.LEFT) - image_bgra = self.image_matrix.get_data() - - image = cv2.cvtColor(image_bgra, cv2.COLOR_BGRA2RGB) - return image - - def _retrieve_depth_map(self) -> NumpyDepthMapType: - assert self.depth_mode != self.NONE_DEPTH_MODE, "Cannot retrieve depth data if depth mode is NONE" - assert self.depth_enabled, "Cannot retrieve depth data if depth is disabled" - self.camera.retrieve_measure(self.depth_matrix, sl.MEASURE.DEPTH) - depth_map = self.depth_matrix.get_data() - return depth_map - - def _retrieve_depth_image(self) -> NumpyIntImageType: - assert self.depth_mode != self.NONE_DEPTH_MODE, "Cannot retrieve depth data if depth mode is NONE" - assert self.depth_enabled, "Cannot retrieve depth data if depth is disabled" - self.camera.retrieve_image(self.depth_image_matrix, sl.VIEW.DEPTH) - image_bgra = self.depth_image_matrix.get_data() - # image = image[..., :3] - image = cv2.cvtColor(image_bgra, cv2.COLOR_BGRA2RGB) - return image - - def _retrieve_colored_point_cloud(self) -> PointCloud: - assert self.depth_mode != self.NONE_DEPTH_MODE, "Cannot retrieve depth data if depth mode is NONE" - assert self.depth_enabled, "Cannot retrieve depth data if depth is disabled" - self.camera.retrieve_measure(self.point_cloud_matrix, sl.MEASURE.XYZ) - # shape (width, height, 4) with the 4th dim being x,y,z,(rgba packed into float) - # can be nan,nan,nan, nan (no point in the point_cloud on this pixel) - # or x,y,z, nan (no color information on this pixel??) - # or x,y,z, value (color information on this pixel) - - point_cloud_XYZ_ = self.point_cloud_matrix.get_data() - - positions = cv2.cvtColor(point_cloud_XYZ_, cv2.COLOR_BGRA2BGR).reshape(-1, 3) - colors = self._retrieve_rgb_image_as_int().reshape(-1, 3) - - return PointCloud(positions, colors) - - def _retrieve_confidence_map(self) -> NumpyFloatImageType: - self.camera.retrieve_measure(self.confidence_matrix, sl.MEASURE.CONFIDENCE) - return self.confidence_matrix.get_data() # single channel float32 image - - def get_colored_point_cloud(self) -> PointCloud: - assert self.depth_mode != self.NONE_DEPTH_MODE, "Cannot retrieve depth data if depth mode is NONE" - assert self.depth_enabled, "Cannot retrieve depth data if depth is disabled" - - self._grab_images() - return self._retrieve_colored_point_cloud() - - @staticmethod - def list_camera_serial_numbers() -> List[str]: - """ - List all connected ZED cameras - can be used to select a device ID or to check if cameras are connected. - """ - device_list = sl.Camera.get_device_list() - return device_list - - # manage resources - # this is important if you want to reuse the camera - # multiple times within a python script, in which case you should release the camera before creating a new object. - # cf. https://stackoverflow.com/questions/865115/how-do-i-correctly-clean-up-a-python-object - def __enter__(self) -> StereoRGBDCamera: - return self - - def __exit__(self, exc_type: Any, exc_value: Any, traceback: Any) -> None: - self.camera.close() - +"""This file is present for backwards compatibility, when we only supported Zed2i cameras, and the Zed2i class was in this file.""" +from airo_camera_toolkit.cameras.zed.zed import * # noqa: F401, F403 +from airo_camera_toolkit.cameras.zed.zed import _test_zed_implementation if __name__ == "__main__": - """this script serves as a 'test' for the zed implementation.""" - from airo_camera_toolkit.cameras.manual_test_hw import manual_test_stereo_rgbd_camera, profile_rgb_throughput - - # zed specific tests: - # - list all serial numbers of the cameras - serial_numbers = Zed2i.list_camera_serial_numbers() - print(serial_numbers) - input("each camera connected to the pc should be listed, press enter to continue") - - # test rgbd stereo camera - - with Zed2i(Zed2i.RESOLUTION_2K, fps=15, depth_mode=Zed2i.PERFORMANCE_DEPTH_MODE) as zed: - print(zed.get_colored_point_cloud().points) # TODO: test the point_cloud more explicity? - manual_test_stereo_rgbd_camera(zed) - - # profile rgb throughput, should be at 60FPS, i.e. 0.017s - - zed = Zed2i(Zed2i.RESOLUTION_720, fps=60) - profile_rgb_throughput(zed) + _test_zed_implementation() From 9311f8912df1f5dcd37b5c6b6812ac289944364d Mon Sep 17 00:00:00 2001 From: Mathieu De Coster Date: Tue, 10 Dec 2024 14:09:20 +0100 Subject: [PATCH 2/6] Update CHANGELOG.md --- CHANGELOG.md | 1 + 1 file changed, 1 insertion(+) diff --git a/CHANGELOG.md b/CHANGELOG.md index 9206cc9..61b7189 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -31,6 +31,7 @@ This project uses a [CalVer](https://calver.org/) versioning scheme with monthly - Dropped support for python 3.8 and added 3.11 to the testing matrix [#103](https://github.com/airo-ugent/airo-mono/issues/103). - Set python version to 3.10 because of an issue with the `ur_rtde` wheels [#121](https://github.com/airo-ugent/airo-mono/issues/121). Updated README.md to reflect this change. - `URrtde` will now try connecting to do control interface up to 3 times before raising a `RuntimeError`. +- Renamed `Zed2i` to `Zed` and `zed2i.py` to `zed.py`, but kept the old names as aliases for backwards compatibility ### Fixed - Fixed bug in `get_colored_point_cloud()` that removed some points see issue #25. From 2ca92a83518f7be2de655d02b90e707b438ae268 Mon Sep 17 00:00:00 2001 From: Mathieu De Coster Date: Tue, 10 Dec 2024 14:10:59 +0100 Subject: [PATCH 3/6] Add @deprecated decorator to Zed2i --- airo-camera-toolkit/airo_camera_toolkit/cameras/zed/zed.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/airo-camera-toolkit/airo_camera_toolkit/cameras/zed/zed.py b/airo-camera-toolkit/airo_camera_toolkit/cameras/zed/zed.py index 9148d08..5312268 100644 --- a/airo-camera-toolkit/airo_camera_toolkit/cameras/zed/zed.py +++ b/airo-camera-toolkit/airo_camera_toolkit/cameras/zed/zed.py @@ -3,6 +3,7 @@ from typing import Any, List, Optional from loguru import logger +from typing_extensions import deprecated try: import pyzed.sl as sl @@ -294,6 +295,7 @@ def __exit__(self, exc_type: Any, exc_value: Any, traceback: Any) -> None: self.camera.close() +@deprecated("Use Zed instead.") class Zed2i(Zed): """Present for backwards compatibility, use Zed instead.""" From 2da645be89c86d7476223ce92fbbb3fc7d9e37d0 Mon Sep 17 00:00:00 2001 From: Mathieu De Coster Date: Tue, 10 Dec 2024 14:21:12 +0100 Subject: [PATCH 4/6] Add -> None type annotation --- airo-camera-toolkit/airo_camera_toolkit/cameras/zed/zed.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/airo-camera-toolkit/airo_camera_toolkit/cameras/zed/zed.py b/airo-camera-toolkit/airo_camera_toolkit/cameras/zed/zed.py index 5312268..d519ae2 100644 --- a/airo-camera-toolkit/airo_camera_toolkit/cameras/zed/zed.py +++ b/airo-camera-toolkit/airo_camera_toolkit/cameras/zed/zed.py @@ -300,7 +300,7 @@ class Zed2i(Zed): """Present for backwards compatibility, use Zed instead.""" -def _test_zed_implementation(): +def _test_zed_implementation() -> None: """this script serves as a 'test' for the zed implementation.""" from airo_camera_toolkit.cameras.manual_test_hw import manual_test_stereo_rgbd_camera, profile_rgb_throughput From a611361c863b01607143c8fe3d876d29b5ca0b80 Mon Sep 17 00:00:00 2001 From: Thomas Lips <37955681+tlpss@users.noreply.github.com> Date: Tue, 10 Dec 2024 14:32:25 +0100 Subject: [PATCH 5/6] update camera readme --- airo-camera-toolkit/airo_camera_toolkit/cameras/README.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/airo-camera-toolkit/airo_camera_toolkit/cameras/README.md b/airo-camera-toolkit/airo_camera_toolkit/cameras/README.md index a09afe1..30d3c1f 100644 --- a/airo-camera-toolkit/airo_camera_toolkit/cameras/README.md +++ b/airo-camera-toolkit/airo_camera_toolkit/cameras/README.md @@ -2,7 +2,7 @@ # Cameras This subpackage contains implementations of the camera interface for the cameras we have at AIRO. -- ZED 2i +- ZED 2 series - Realsense D400 series It also contains code to enable multiprocessed use of the camera streams: [multiprocessed camera](./multiprocess/) @@ -24,5 +24,5 @@ Each camera implementation can be run as a script and will execute the relevant For example, to test your ZED installation: ``` conda activate airo-mono -python3 zed2i.py -``` \ No newline at end of file +python3 zed.py +``` From 3701a33980f2c14459dd8c7d5196441356fb0f7e Mon Sep 17 00:00:00 2001 From: Mathieu De Coster Date: Tue, 10 Dec 2024 14:50:49 +0100 Subject: [PATCH 6/6] Rename all occurrences of Zed2i to Zed in airo-mono --- README.md | 4 ++-- airo-camera-toolkit/README.md | 4 ++-- .../cameras/camera_discovery.py | 4 ++-- .../cameras/multiprocess/README.md | 2 +- .../multiprocess/multiprocess_rgb_camera.py | 10 +++++----- .../multiprocess/multiprocess_rgbd_camera.py | 8 ++++---- .../multiprocess_stereo_rgbd_camera.py | 8 ++++---- .../cameras/zed/installation.md | 2 +- .../airo_camera_toolkit/cameras/zed/zed.py | 18 ++++++------------ .../airo_camera_toolkit/cameras/zed/zed2i.py | 9 ++++++++- .../scripts/live_charuco_pose.py | 4 ++-- 11 files changed, 37 insertions(+), 36 deletions(-) diff --git a/README.md b/README.md index d4a6ccc..7d9e1ab 100644 --- a/README.md +++ b/README.md @@ -54,13 +54,13 @@ pip install airo-camera-toolkit airo-robots ``` And writing a simple script: ```python -from airo_camera_toolkit.cameras.zed.zed2i import Zed2i +from airo_camera_toolkit.cameras.zed.zed import Zed from airo_robots.manipulators.hardware.ur_rtde import URrtde from airo_robots.grippers.hardware.robotiq_2f85_urcap import Robotiq2F85 robot_ip_address = "10.40.0.162" -camera = Zed2i() +camera = Zed() robot = URrtde(ip_address=robot_ip_address) gripper = Robotiq2F85(ip_address=robot_ip_address) diff --git a/airo-camera-toolkit/README.md b/airo-camera-toolkit/README.md index bbde343..8cf6737 100644 --- a/airo-camera-toolkit/README.md +++ b/airo-camera-toolkit/README.md @@ -34,11 +34,11 @@ pip install .[hand-eye-calibration] ## Getting started with cameras Camera can be accessed by instantiating the corresponding class:, e.g. for a ZED camera: ```python -from airo_camera_toolkit.cameras.zed2i import Zed2i +from airo_camera_toolkit.cameras.zed import Zed from airo_camera_toolkit.utils import ImageConverter import cv2 -camera = Zed2i(Zed2i.RESOLUTION_720, fps=30) +camera = Zed(Zed.RESOLUTION_720, fps=30) while True: image_rgb_float = camera.get_rgb_image() diff --git a/airo-camera-toolkit/airo_camera_toolkit/cameras/camera_discovery.py b/airo-camera-toolkit/airo_camera_toolkit/cameras/camera_discovery.py index af00819..aab0630 100644 --- a/airo-camera-toolkit/airo_camera_toolkit/cameras/camera_discovery.py +++ b/airo-camera-toolkit/airo_camera_toolkit/cameras/camera_discovery.py @@ -44,9 +44,9 @@ def discover_camera(brand: Optional[str], serial_number: Optional[str] = None, * brand_enum = CameraBrand(brand) # Attempt to convert to enum if brand_enum == CameraBrand.ZED: - from airo_camera_toolkit.cameras.zed.zed2i import Zed2i + from airo_camera_toolkit.cameras.zed.zed import Zed - camera = Zed2i(serial_number=serial_number, **kwargs) + camera = Zed(serial_number=serial_number, **kwargs) elif brand_enum == CameraBrand.REALSENSE: from airo_camera_toolkit.cameras.realsense.realsense import Realsense diff --git a/airo-camera-toolkit/airo_camera_toolkit/cameras/multiprocess/README.md b/airo-camera-toolkit/airo_camera_toolkit/cameras/multiprocess/README.md index 92a4add..337c2f3 100644 --- a/airo-camera-toolkit/airo_camera_toolkit/cameras/multiprocess/README.md +++ b/airo-camera-toolkit/airo_camera_toolkit/cameras/multiprocess/README.md @@ -29,7 +29,7 @@ The receiver is subclass of `RGBCamera` which ensures that it follows the interf ## Usage See the main function in [multiprocess_rgb_camera.py](./multiprocess_rgb_camera.py) for a simple example of how to use these classes with a ZED camera. -The main difference with the regular workflow is that instead of instantiating a `Zed2i` object, you now have to first create a `MultiprocessRGBPublisher` with the class and its kwargs, and then one or more `MultiprocessRGBReceiver`s. +The main difference with the regular workflow is that instead of instantiating a `Zed` object, you now have to first create a `MultiprocessRGBPublisher` with the class and its kwargs, and then one or more `MultiprocessRGBReceiver`s. > :information_source: Similar to how regular `RGBCamera`s behave, `MultiprocessRGBReceiver`s will block until a new image is available. diff --git a/airo-camera-toolkit/airo_camera_toolkit/cameras/multiprocess/multiprocess_rgb_camera.py b/airo-camera-toolkit/airo_camera_toolkit/cameras/multiprocess/multiprocess_rgb_camera.py index 7a623ba..44d8002 100644 --- a/airo-camera-toolkit/airo_camera_toolkit/cameras/multiprocess/multiprocess_rgb_camera.py +++ b/airo-camera-toolkit/airo_camera_toolkit/cameras/multiprocess/multiprocess_rgb_camera.py @@ -67,7 +67,7 @@ def __init__( """Instantiates the publisher. Note that the publisher (and its process) will not start until start() is called. Args: - camera_cls (type): The class e.g. Zed2i that this publisher will instantiate. + camera_cls (type): The class e.g. Zed that this publisher will instantiate. camera_kwargs (dict, optional): The kwargs that will be passed to the camera_cls constructor. shared_memory_namespace (str, optional): The string that will be used to prefix the shared memory blocks that this class will create. """ @@ -413,21 +413,21 @@ def __del__(self) -> None: """example of how to use the MultiprocessRGBPublisher and MultiprocessRGBReceiver. You can also use the MultiprocessRGBReceiver in a different process (e.g. in a different python script) """ - from airo_camera_toolkit.cameras.zed.zed2i import Zed2i + from airo_camera_toolkit.cameras.zed.zed import Zed multiprocessing.set_start_method("spawn") - resolution = Zed2i.RESOLUTION_2K + resolution = Zed.RESOLUTION_2K camera_fps = 15 namespace = "camera" # Creating and starting the publisher publisher = MultiprocessRGBPublisher( - Zed2i, + Zed, camera_kwargs={ "resolution": resolution, "fps": camera_fps, - "depth_mode": Zed2i.NEURAL_DEPTH_MODE, + "depth_mode": Zed.NEURAL_DEPTH_MODE, }, shared_memory_namespace=namespace, ) diff --git a/airo-camera-toolkit/airo_camera_toolkit/cameras/multiprocess/multiprocess_rgbd_camera.py b/airo-camera-toolkit/airo_camera_toolkit/cameras/multiprocess/multiprocess_rgbd_camera.py index 46e268c..650627e 100644 --- a/airo-camera-toolkit/airo_camera_toolkit/cameras/multiprocess/multiprocess_rgbd_camera.py +++ b/airo-camera-toolkit/airo_camera_toolkit/cameras/multiprocess/multiprocess_rgbd_camera.py @@ -389,19 +389,19 @@ def __del__(self) -> None: import multiprocessing - from airo_camera_toolkit.cameras.zed.zed2i import Zed2i + from airo_camera_toolkit.cameras.zed.zed import Zed multiprocessing.set_start_method("spawn") - resolution = Zed2i.RESOLUTION_2K + resolution = Zed.RESOLUTION_2K camera_fps = 15 publisher = MultiprocessRGBDPublisher( - Zed2i, + Zed, camera_kwargs={ "resolution": resolution, "fps": camera_fps, - "depth_mode": Zed2i.NEURAL_DEPTH_MODE, + "depth_mode": Zed.NEURAL_DEPTH_MODE, }, ) diff --git a/airo-camera-toolkit/airo_camera_toolkit/cameras/multiprocess/multiprocess_stereo_rgbd_camera.py b/airo-camera-toolkit/airo_camera_toolkit/cameras/multiprocess/multiprocess_stereo_rgbd_camera.py index d436971..77b1e0e 100644 --- a/airo-camera-toolkit/airo_camera_toolkit/cameras/multiprocess/multiprocess_stereo_rgbd_camera.py +++ b/airo-camera-toolkit/airo_camera_toolkit/cameras/multiprocess/multiprocess_stereo_rgbd_camera.py @@ -281,22 +281,22 @@ def __del__(self) -> None: import multiprocessing - from airo_camera_toolkit.cameras.zed.zed2i import Zed2i + from airo_camera_toolkit.cameras.zed.zed import Zed multiprocessing.set_start_method("spawn") - resolution = Zed2i.RESOLUTION_2K + resolution = Zed.RESOLUTION_2K camera_fps = 15 # import os # os.environ["CUDA_VISIBLE_DEVICES"] = "3" publisher = MultiprocessStereoRGBDPublisher( - Zed2i, + Zed, camera_kwargs={ "resolution": resolution, "fps": camera_fps, - "depth_mode": Zed2i.NEURAL_DEPTH_MODE, + "depth_mode": Zed.NEURAL_DEPTH_MODE, }, log_debug=True, ) diff --git a/airo-camera-toolkit/airo_camera_toolkit/cameras/zed/installation.md b/airo-camera-toolkit/airo_camera_toolkit/cameras/zed/installation.md index 6a34b93..6035e96 100644 --- a/airo-camera-toolkit/airo_camera_toolkit/cameras/zed/installation.md +++ b/airo-camera-toolkit/airo_camera_toolkit/cameras/zed/installation.md @@ -46,7 +46,7 @@ Now We will test whether our `airo_camera_toolkit can access the ZED cameras. In this directory run: ``` conda activate airo-mono -python zed2i.py +python zed.py ``` Complete the prompts. If everything looks normal, congrats, you successfully completed the installation! :tada: diff --git a/airo-camera-toolkit/airo_camera_toolkit/cameras/zed/zed.py b/airo-camera-toolkit/airo_camera_toolkit/cameras/zed/zed.py index d519ae2..d530b74 100644 --- a/airo-camera-toolkit/airo_camera_toolkit/cameras/zed/zed.py +++ b/airo-camera-toolkit/airo_camera_toolkit/cameras/zed/zed.py @@ -3,7 +3,6 @@ from typing import Any, List, Optional from loguru import logger -from typing_extensions import deprecated try: import pyzed.sl as sl @@ -90,22 +89,22 @@ def __init__( # type: ignore[no-any-unimported] self._resolution = resolution self.fps = fps self.depth_mode = depth_mode - self.serial_number = serial_number + self.serial_number = int(serial_number) if serial_number else None self.camera = sl.Camera() # TODO: create a configuration class for the camera parameters self.camera_params = sl.InitParameters() - if serial_number: - self.camera_params.set_from_serial_number(int(serial_number)) + if self.serial_number: + self.camera_params.set_from_serial_number(self.serial_number) if svo_filepath: input_type = sl.InputType() input_type.set_from_svo_file(svo_filepath) self.camera_params = sl.InitParameters(input_t=input_type, svo_real_time_mode=False) - self.camera_params.camera_resolution = Zed2i.resolution_to_identifier_dict[resolution] + self.camera_params.camera_resolution = Zed.resolution_to_identifier_dict[resolution] self.camera_params.camera_fps = fps # https://www.stereolabs.com/docs/depth-sensing/depth-settings/ self.camera_params.depth_mode = depth_mode @@ -123,7 +122,7 @@ def __init__( # type: ignore[no-any-unimported] status = self.camera.open(self.camera_params) if status == sl.ERROR_CODE.SUCCESS: break - logger.info(f"Opening Zed2i camera failed, attempt {i + 1}/{N_OPEN_ATTEMPTS}") + logger.info(f"Opening Zed camera failed, attempt {i + 1}/{N_OPEN_ATTEMPTS}") if self.serial_number: logger.info(f"Rebooting {self.serial_number}") sl.Camera.reboot(self.serial_number) @@ -132,7 +131,7 @@ def __init__( # type: ignore[no-any-unimported] self.camera = sl.Camera() if status != sl.ERROR_CODE.SUCCESS: - raise IndexError(f"Could not open Zed2i camera, error = {status}") + raise IndexError(f"Could not open Zed camera, error = {status}") # TODO: create a configuration class for the runtime parameters self.runtime_params = sl.RuntimeParameters() @@ -295,11 +294,6 @@ def __exit__(self, exc_type: Any, exc_value: Any, traceback: Any) -> None: self.camera.close() -@deprecated("Use Zed instead.") -class Zed2i(Zed): - """Present for backwards compatibility, use Zed instead.""" - - def _test_zed_implementation() -> None: """this script serves as a 'test' for the zed implementation.""" from airo_camera_toolkit.cameras.manual_test_hw import manual_test_stereo_rgbd_camera, profile_rgb_throughput diff --git a/airo-camera-toolkit/airo_camera_toolkit/cameras/zed/zed2i.py b/airo-camera-toolkit/airo_camera_toolkit/cameras/zed/zed2i.py index 2d31ed0..dafcfef 100644 --- a/airo-camera-toolkit/airo_camera_toolkit/cameras/zed/zed2i.py +++ b/airo-camera-toolkit/airo_camera_toolkit/cameras/zed/zed2i.py @@ -1,6 +1,13 @@ """This file is present for backwards compatibility, when we only supported Zed2i cameras, and the Zed2i class was in this file.""" from airo_camera_toolkit.cameras.zed.zed import * # noqa: F401, F403 -from airo_camera_toolkit.cameras.zed.zed import _test_zed_implementation +from airo_camera_toolkit.cameras.zed.zed import Zed, _test_zed_implementation +from typing_extensions import deprecated + + +@deprecated("Use Zed instead.") +class Zed2i(Zed): + """Present for backwards compatibility, use Zed instead.""" + if __name__ == "__main__": _test_zed_implementation() diff --git a/airo-camera-toolkit/scripts/live_charuco_pose.py b/airo-camera-toolkit/scripts/live_charuco_pose.py index bb3ae12..c8e0400 100644 --- a/airo-camera-toolkit/scripts/live_charuco_pose.py +++ b/airo-camera-toolkit/scripts/live_charuco_pose.py @@ -1,9 +1,9 @@ import cv2 from airo_camera_toolkit.calibration.fiducial_markers import detect_charuco_board, draw_frame_on_image -from airo_camera_toolkit.cameras.zed.zed2i import Zed2i +from airo_camera_toolkit.cameras.zed.zed import Zed from airo_camera_toolkit.utils.image_converter import ImageConverter -camera = Zed2i(fps=30) +camera = Zed(fps=30) intrinsics = camera.intrinsics_matrix() window_name = "Charuco Pose"