# ZED SDK 5.3.1 — python API reference > Per-symbol API reference for the ZED SDK python API, generated from the > source headers/stubs. For concepts, tutorials and usage examples see the > main documentation: https://docs.stereolabs.com/llms-full.txt > (index: https://docs.stereolabs.com/llms.txt). ## Contents - Camera - InitParameters - RuntimeParameters - Mat - ERROR_CODE - CameraParameters - CalibrationParameters - Pose - SensorsData - PositionalTrackingParameters - RecordingParameters - StreamingParameters - ObjectDetectionParameters - BodyTrackingParameters - BarometerData - BatchParameters - Bodies - BodiesBatch - BodyData - BodyTrackingFusionParameters - BodyTrackingFusionRuntimeParameters - BodyTrackingRuntimeParameters - BodyTrackingSensorsParameters - BodyTrackingSensorsRuntimeParameters - CameraConfiguration - CameraIdentifier - CameraInformation - CameraMetrics - CameraOne - CameraOneConfiguration - CameraOneInformation - Chunk - CommunicationParameters - CustomBoxObjectData - CustomMaskObjectData - CustomObjectDetectionProperties - CustomObjectDetectionRuntimeParameters - DeviceProperties - ECEF - ENU - FusedPointCloud - FusedPositionalTrackingStatus - Fusion - FusionConfiguration - FusionMetrics - GNSSCalibrationParameters - GNSSData - GeoConverter - GeoPose - HealthStatus - IMUData - InitFusionParameters - InitLidarParameters - InitParametersOne - InitSensorsParameters - InputType - KeyFrame - Landmark - Landmark2D - LatLng - Lidar - LidarCalibration - LidarDeviceProperties - LidarInformation - LidarSensorConfiguration - MagnetometerData - Matrix3f - Matrix4f - Mesh - MeshFilterParameters - ObjectData - ObjectDetectionFusionParameters - ObjectDetectionRuntimeParameters - ObjectDetectionSensorsParameters - ObjectTrackingParameters - ObjectTrackingParametersProxy - Objects - ObjectsBatch - Orientation - Plane - PlaneDetectionParameters - PointCloudChunk - PositionalTrackingFusionParameters - PositionalTrackingLidarParameters - PositionalTrackingSensorsParameters - PositionalTrackingStatus - RecordingLidarParameters - RecordingSensorsParameters - RecordingStatus - Rect - RegionOfInterestParameters - Resolution - Rotation - RuntimeSensorsParameters - SVOData - SensorDeviceIdentifier - SensorList - SensorParameters - Sensors - SensorsConfiguration - SpatialMappingFusionParameters - SpatialMappingParameters - StreamingProperties - StreamingSensorList - StreamingSensorsParameters - SynchronizationParameter - TemperatureData - Tensor - TensorParameters - Timestamp - Transform - Translation - UTM - VoxelMeasureParameters - AI_MODELS - AREA_EXPORTING_STATE - BODY_18_PARTS - BODY_34_PARTS - BODY_38_PARTS - BODY_FORMAT - BODY_KEYPOINTS_SELECTION - BODY_TRACKING_MODEL - BUS_TYPE - CAMERA_MOTION_STATE - CAMERA_STATE - COMM_TYPE - COORDINATE_SYSTEM - COPY_TYPE - DEPTH_MODE - FLIP_MODE - FUSION_ERROR_CODE - FUSION_REFERENCE_FRAME - GNSS_FUSION_STATUS - GNSS_MODE - GNSS_STATUS - HEADING_STATE - INFERENCE_PRECISION - INPUT_TYPE - LIDAR_MEASURE - LIDAR_MODE - LIDAR_MULTICAST_MODE - LIDAR_VIEW - MAPPING_RANGE - MAPPING_RESOLUTION - MAT_TYPE - MEASURE - MEM - MESH_CREATION - MESH_FILE_FORMAT - MESH_FILTER - MESH_TEXTURE_FORMAT - MODEL - MODULE - OBJECT_ACCELERATION_PRESET - OBJECT_ACTION_STATE - OBJECT_CLASS - OBJECT_DETECTION_MODEL - OBJECT_FILTERING_MODE - OBJECT_SUBCLASS - OBJECT_TRACKING_STATE - ODOMETRY_STATUS - PLANE_TYPE - POSITIONAL_TRACKING_FUSION_STATUS - POSITIONAL_TRACKING_MODE - POSITIONAL_TRACKING_STATE - POSITION_TYPE - RECORDING_FORMAT - REFERENCE_FRAME - REGION_OF_INTEREST_AUTO_DETECTION_STATE - RESOLUTION - SENDER_ERROR_CODE - SENSORS_ERROR_CODE - SENSORS_EXECUTION_MODE - SENSORS_REFERENCE_FRAME - SENSORS_SYNC_POLICY - SENSORS_TYPE - SENSORS_UNIT - SENSOR_LOCATION - SENSOR_STATE - SENSOR_TYPE - SIDE - SPATIAL_MAPPING_STATE - SPATIAL_MAP_TYPE - SPATIAL_MEMORY_STATUS - STREAMING_CODEC - SVO_COMPRESSION_MODE - SVO_ENCODING_PRESET - TENSOR_COLOR_FORMAT - TENSOR_LAYOUT - TENSOR_PIXEL_TYPE - TIMESTAMP_CLOCK - TIME_REFERENCE - TYPE_OF_INPUT_TYPE - UNIT - VIDEO_SETTINGS - VIEW - VIEW_COLOR_MAP - VOXELIZATION_MODE - Module functions --- # Camera This class serves as the primary interface between the camera and the various features provided by the SDK. It enables seamless integration and access to a wide array of capabilities, including video streaming, depth sensing, object tracking, mapping, and much more. A standard program will use the Camera class like this: import pyzed.sl as sl def main(): # --- Initialize a Camera object and open the ZED # Create a ZED camera object zed = sl.Camera() # Set configuration parameters init_params = sl.InitParameters() init_params.camera_resolution = sl.RESOLUTION.HD720 # Use HD720 video mode for USB cameras # init_params.camera_resolution = sl.RESOLUTION.HD1200 # Use HD1200 video mode for GMSL cameras init_params.camera_fps = 60 # Set fps at 60 # Open the camera err = zed.open(init_params) if err != sl.ERROR_CODE.SUCCESS: print(repr(err)) exit(-1) runtime_param = sl.RuntimeParameters() # --- Main loop grabbing images and depth values # Capture 50 frames and stop i = 0 image = sl.Mat() depth = sl.Mat() while i < 50 : # Grab an image if zed.grab(runtime_param) == sl.ERROR_CODE.SUCCESS: # A new image is available if grab() returns SUCCESS # Display a pixel color zed.retrieve_image(image, sl.VIEW.LEFT) # Get the left image err, center_rgb = image.get_value(image.get_width() / 2, image.get_height() / 2) if err == sl.ERROR_CODE.SUCCESS: print("Image ", i, " center pixel R:", int(center_rgb[0]), " G:", int(center_rgb[1]), " B:", int(center_rgb[2])) else: print("Image ", i, " error:", err) # Display a pixel depth zed.retrieve_measure(depth, sl.MEASURE.DEPTH) # Get the depth map err, center_depth = depth.get_value(depth.get_width() / 2, depth.get_height() /2) if err == sl.ERROR_CODE.SUCCESS: print("Image ", i," center depth:", center_depth) else: print("Image ", i, " error:", err) i = i+1 # --- Close the Camera zed.close() return 0 if __name__ == "__main__": main() ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `close(self) -> None` Close an opened camera. If open() has been called, this method will close the connection to the camera (or the SVO file) and free the corresponding memory. If open() wasn't called or failed, this method won't have any effect. **Note:** If an asynchronous task is running within the Camera object, like save_area_map(), this method will wait for its completion. **Note:** To apply a new InitParameters, you will need to close the camera first and then open it again with the new InitParameters values. **Warning:** If the CUDA context was created by open(), this method will destroy it. **Warning:** Therefore you need to make sure to delete your GPU sl.Mat objects before the context is destroyed. ### `open(self, py_init=None) -> ERROR_CODE` Opens the ZED camera from the provided InitParameters. The method will also check the hardware requirements and run a self-calibration. :param py_init: A structure containing all the initial parameters. Default: a preset of InitParameters. :return: An error code giving information about the internal process. If ERROR_CODE.SUCCESS is returned, the camera is ready to use. Every other code indicates an error and the program should be stopped. Here is the proper way to call this function: zed = sl.Camera() # Create a ZED camera object init_params = sl.InitParameters() # Set configuration parameters init_params.camera_resolution = sl.RESOLUTION.HD720 # Use HD720 video mode init_params.camera_fps = 60 # Set fps at 60 # Open the camera err = zed.open(init_params) if (err != sl.ERROR_CODE.SUCCESS) : print(repr(err)) # Display the error exit(-1) **Note:** If you are having issues opening a camera, the diagnostic tool provided in the SDK can help you identify to problems. - **Windows:** C:\Program Files (x86)\ZED SDK\tools\ZED Diagnostic.exe - **Linux:** /usr/local/zed/tools/ZED Diagnostic **Note:** If this method is called on an already opened camera, close() will be called. ### `is_opened(self) -> bool` Reports if the camera has been successfully opened. It has the same behavior as checking if open() returns ERROR_CODE.SUCCESS. :return: True if the ZED camera is already setup, otherwise false. ### `read(self) -> ERROR_CODE` Read the latest images and IMU from the camera and rectify the images. This method is meant to be called frequently in the main loop of your application. **Note:** If no new frames is available until timeout is reached, read() will return ERROR_CODE "ERROR_CODE::CAMERA_NOT_DETECTED" since the camera has probably been disconnected. **Note:** Returned errors can be displayed using toString(). :return: ERROR_CODE "ERROR_CODE::SUCCESS" means that no problem was encountered. ### `grab(self, py_runtime=None) -> ERROR_CODE` This method will grab the latest images from the camera, rectify them, and compute the retrieve_measure() "measurements" based on the RuntimeParameters provided (depth, point cloud, tracking, etc.) As measures are created in this method, its execution can last a few milliseconds, depending on your parameters and your hardware. The exact duration will mostly depend on the following parameters: - InitParameters.enable_right_side_measure : Activating this parameter increases computation time. - InitParameters.camera_resolution : Lower resolutions are faster to compute. - enable_positional_tracking() : Activating the tracking is an additional load. - RuntimeParameters.enable_depth : Avoiding the depth computation must be faster. However, it is required by most SDK features (tracking, spatial mapping, plane estimation, etc.) - InitParameters.depth_mode : DEPTH_MODE.PERFORMANCE will run faster than DEPTH_MODE.ULTRA. - InitParameters.depth_stabilization : Stabilizing the depth requires an additional computation load as it enables tracking. This method is meant to be called frequently in the main loop of your application. **Note:** Since ZED SDK 3.0, this method is blocking. It means that grab() will wait until a new frame is detected and available. **Note:** If no new frames is available until timeout is reached, grab() will return ERROR_CODE.CAMERA_NOT_DETECTED since the camera has probably been disconnected. :param py_runtime: A structure containing all the runtime parameters. Default: a preset of RuntimeParameters. :return: ERROR_CODE.SUCCESS means that no problem was encountered. **Note:** Returned errors can be displayed using ``str()``. # Set runtime parameters after opening the camera runtime_param = sl.RuntimeParameters() image = sl.Mat() while True: # Grab an image if zed.grab(runtime_param) == sl.ERROR_CODE.SUCCESS: # A new image is available if grab() returns SUCCESS zed.retrieve_image(image, sl.VIEW.LEFT) # Get the left image # Use the image for your application ### `retrieve_image(self, py_mat, view: VIEW=VIEW.LEFT, mem_type: MEM=MEM.CPU, resolution=None) -> ERROR_CODE` Retrieves images from the camera (or SVO file). Multiple images are available along with a view of various measures for display purposes. Available images and views are listed here. As an example, VIEW.DEPTH can be used to get a gray-scale version of the depth map, but the actual depth values can be retrieved using retrieve_measure() . **Pixels** Most VIEW modes output image with 4 channels as BGRA (Blue, Green, Red, Alpha), for more information see enum VIEW **Memory** By default, images are copied from GPU memory to CPU memory (RAM) when this function is called. If your application can use GPU images, using the **type** parameter can increase performance by avoiding this copy. If the provided sl.Mat object is already allocated and matches the requested image format, memory won't be re-allocated. **Image size** By default, images are returned in the resolution provided by Resolution "get_camera_information().camera_configuration.resolution". However, you can request custom resolutions. For example, requesting a smaller image can help you speed up your application. **Warning:** A sl.Mat resolution higher than the camera resolution **cannot** be requested. **Warning:** If VIEW is VIEW "VIEW::LEFT_NV12_UNRECTIFIED" or VIEW "VIEW::RIGHT_NV12_UNRECTIFIED", **image_size must be native, and **type must be MEM "MEM::GPU". :param py_mat: The sl.Mat to store the image. (Direction: out) :param view: Defines the image you want (see VIEW). Default: VIEW.LEFT. (Direction: in) :param mem_type: Defines on which memory the image should be allocated. Default: MEM.CPU. (Direction: in) :param resolution: If specified, defines the Resolution of the output sl.Mat. If set to Resolution "Resolution(0,0)", the camera resolution or InitParameters.maximum_working_resolution will be taken, whichever is the smallest. Default: (0,0). (Direction: in) To override the default and choose a different size, the environment variable "ZED_SDK_DISABLE_AUTO_RETRIEVE_RESOLUTION" can be set to 1. For instance on Linux, in a terminal before running your program, call "export ZED_SDK_DISABLE_AUTO_RETRIEVE_RESOLUTION=1", or call sl.set_environment_variable("ZED_SDK_DISABLE_AUTO_RETRIEVE_RESOLUTION", "1") at the beginning of the code. :return: ERROR_CODE.SUCCESS if the method succeeded. :return: ERROR_CODE.INVALID_FUNCTION_PARAMETERS if the view mode requires a module not enabled (VIEW.DEPTH with DEPTH_MODE.NONE for example). :return: ERROR_CODE.INVALID_RESOLUTION if the resolution is higher than one provided by Resolution "get_camera_information().camera_configuration.resolution". :return: ERROR_CODE.FAILURE if another error occurred. **Note:** As this method retrieves the images grabbed by the grab() method, it should be called afterward. # create sl.Mat objects to store the images left_image = sl.Mat() while True: # Grab an image if zed.grab() == sl.ERROR_CODE.SUCCESS: # A new image is available if grab() returns SUCCESS zed.retrieve_image(left_image, sl.VIEW.LEFT) # Get the rectified left image # Display the center pixel colors err, left_center = left_image.get_value(left_image.get_width() / 2, left_image.get_height() / 2) if err == sl.ERROR_CODE.SUCCESS: print("left_image center pixel R:", int(left_center[0]), " G:", int(left_center[1]), " B:", int(left_center[2])) else: print("error:", err) ### `retrieve_tensor(self, dest, params) -> None` Retrieved a sl::Tensor, containing the input image pre-processed for inference with SVO or live camera. This method provides a way to obtain the pre-processed input image in a format suitable for deep learning inference tasks. The retrieved Tensor is allocated on the GPU, allowing for efficient processing and integration with deep learning frameworks. The pre-processing steps applied to the input image include resizing, normalization, and any other transformations required to prepare the image for inference. This method is particularly useful when working with deep learning models that require specific input formats and pre-processing steps. By retrieving the pre-processed Tensor directly from the Camera class, users can streamline their workflow and ensure compatibility with their deep learning pipelines. **Note:** This method requires that the camera has been opened in either LIVE mode, SVO mode or STREAM mode. **Note:** The retrieved Tensor is allocated on the GPU, so ensure that your system has sufficient GPU memory to accommodate the Tensor size. :param dest: The Tensor to store the pre-processed input image for inference. :param params: Options to configure the pre-processing steps applied to the input image. :return: ERROR_CODE "ERROR_CODE::SUCCESS" if the method succeeded. :return: ERROR_CODE "ERROR_CODE::INVALID_FUNCTION_PARAMETERS" if the provided params are invalid. :return: ERROR_CODE "ERROR_CODE::CAMERA_NOT_INITIALIZED" if the camera is not opened. :return: ERROR_CODE "ERROR_CODE::FAILURE" if another error occurred. ### `retrieve_measure(self, py_mat, measure: MEASURE=MEASURE.DEPTH, mem_type: MEM=MEM.CPU, resolution=None) -> ERROR_CODE` Computed measures, like depth, point cloud, or normals, can be retrieved using this method. Multiple measures are available after a grab() call. A full list is available here. **Memory** By default, images are copied from GPU memory to CPU memory (RAM) when this function is called. If your application can use GPU images, using the **type parameter can increase performance by avoiding this copy. If the provided Mat object is already allocated and matches the requested image format, memory won't be re-allocated. **Measure size** By default, measures are returned in the resolution provided by get_camera_information() in CameraInformations.camera_resolution . However, custom resolutions can be requested. For example, requesting a smaller measure can help you speed up your application. **Warning:** A sl.Mat resolution higher than the camera resolution **cannot** be requested. :param py_mat: The sl.Mat to store the measures. (Direction: out) :param measure: Defines the measure you want (see MEASURE). Default: MEASURE.DEPTH. (Direction: in) :param mem_type: Defines on which memory the image should be allocated. Default: MEM.CPU (you cannot change this default value). (Direction: in) :param resolution: If specified, defines the Resolution of the output sl.Mat. If set to Resolution "Resolution(0,0)", the camera resolution or InitParameters.maximum_working_resolution will be taken, whichever is the smallest. Default: (0,0). (Direction: in) To override the default and choose a different size, the environment variable "ZED_SDK_DISABLE_AUTO_RETRIEVE_RESOLUTION" can be set to 1. For instance on Linux, in a terminal before running your program, call "export ZED_SDK_DISABLE_AUTO_RETRIEVE_RESOLUTION=1", or call sl.set_environment_variable("ZED_SDK_DISABLE_AUTO_RETRIEVE_RESOLUTION", "1") at the beginning of the code. :return: ERROR_CODE.SUCCESS if the method succeeded. :return: ERROR_CODE.INVALID_FUNCTION_PARAMETERS if the view mode requires a module not enabled (VIEW.DEPTH with DEPTH_MODE.NONE for example). :return: ERROR_CODE.INVALID_RESOLUTION if the resolution is higher than one provided by Resolution "get_camera_information().camera_configuration.resolution". :return: ERROR_CODE.FAILURE if another error occured. **Note:** As this method retrieves the images grabbed by the grab() method, it should be called afterward. depth_map = sl.Mat() point_cloud = sl.Mat() resolution = zed.get_camera_information().camera_configuration.resolution x = int(resolution.width / 2) # Center coordinates y = int(resolution.height / 2) while True : if zed.grab() == sl.ERROR_CODE.SUCCESS: # Grab an image zed.retrieve_measure(depth_map, sl.MEASURE.DEPTH) # Get the depth map # Read a depth value err, center_depth = depth_map.get_value(x, y) # each depth map pixel is a float value if err == sl.ERROR_CODE.SUCCESS: # + Inf is "too far", -Inf is "too close", Nan is "unknown/occlusion" print("Depth value at center:", center_depth, init_params.coordinate_units) zed.retrieve_measure(point_cloud, sl.MEASURE.XYZRGBA) # Get the point cloud # Read a point cloud value err, pc_value = point_cloud.get_value(x, y) # each point cloud pixel contains 4 floats, so we are using a numpy array # Get 3D coordinates if err == sl.ERROR_CODE.SUCCESS: print("Point cloud coordinates at center: X=", pc_value[0], ", Y=", pc_value[1], ", Z=", pc_value[2]) # Get color information using Python struct package to unpack the unsigned char array containing RGBA values import struct packed = struct.pack('f', pc_value[3]) char_array = struct.unpack('BBBB', packed) print("Color values at center: R=", char_array[0], ", G=", char_array[1], ", B=", char_array[2], ", A=", char_array[3]) ### `retrieve_voxel_measure(self, py_mat, measure: MEASURE=MEASURE.XYZRGBA, mem_type: MEM=MEM.CPU, params=None) -> ERROR_CODE` Retrieves a voxel-decimated point cloud measure. Returns an unorganized 1D point cloud (height=1) where the scene has been decimated into a voxel grid. Use Mat.get_width() to get the point count. :param py_mat: The Mat to store the voxel point cloud. :param measure: The point cloud measure to retrieve. Default: MEASURE.XYZRGBA. Only point cloud measures are supported (XYZ, XYZRGBA, XYZBGRA, XYZARGB, XYZABGR and RIGHT variants). :param mem_type: Whether the output should be on CPU or GPU. Default: MEM.CPU. :param params: Voxel decimation parameters. See VoxelMeasureParameters. If None, defaults are used. :return: An ERROR_CODE indicating success or failure. ### `set_region_of_interest(self, py_mat, modules=[MODULE.ALL]) -> ERROR_CODE` Defines a region of interest to focus on for all the SDK, discarding other parts. :param roi_mask: The Mat defining the requested region of interest, pixels lower than 127 will be discarded from all modules: depth, positional tracking, etc. If empty, set all pixels as valid. The mask can be either at lower or higher resolution than the current images. :return: An ERROR_CODE if something went wrong. **Note:** The method support MAT_TYPE "U8_C1/U8_C3/U8_C4" images type. ### `get_region_of_interest(self, py_mat, resolution=None, module: MODULE=MODULE.ALL) -> ERROR_CODE` Get the previously set or computed region of interest :param roi_mask: The Mat returned :param image_size: The optional size of the returned mask :return: An ERROR_CODE if something went wrong. ### `start_region_of_interest_auto_detection(self, roi_param=None) -> ERROR_CODE` Start the auto detection of a region of interest to focus on for all the SDK, discarding other parts. This detection is based on the general motion of the camera combined with the motion in the scene. The camera must move for this process, an internal motion detector is used, based on the Positional Tracking module. It requires a few hundreds frames of motion to compute the mask. :param roi_param: The RegionOfInterestParameters defining parameters for the detection **Note:** This module is expecting a static portion, typically a fairly close vehicle hood at the bottom of the image. This module may not work correctly or detect incorrect background area, especially with slow motion, if there's no static element. This module work asynchronously, the status can be obtained using get_region_of_interest_auto_detection_status(), the result is either auto applied, or can be retrieve using get_region_of_interest function. :return: An ERROR_CODE if something went wrong. ### `get_region_of_interest_auto_detection_status(self) -> REGION_OF_INTEREST_AUTO_DETECTION_STATE` Return the status of the automatic Region of Interest Detection The automatic Region of Interest Detection is enabled by using startRegionOfInterestAutoDetection :return: REGION_OF_INTEREST_AUTO_DETECTION_STATE the status ### `start_publishing(self, communication_parameters) -> ERROR_CODE` Set this camera as a data provider for the Fusion module. Metadata is exchanged with the Fusion. :param communication_parameters: A structure containing all the initial parameters. Default: a preset of CommunicationParameters. :return: ERROR_CODE.SUCCESS if everything went fine, ERROR_CODE.FAILURE otherwise. ### `stop_publishing(self) -> ERROR_CODE` Set this camera as normal camera (without data providing). Stop to send camera data to fusion. :return: ERROR_CODE.SUCCESS if everything went fine, ERROR_CODE.FAILURE otherwise. ### `get_communication_parameters(self) -> CommunicationParameters` Returns the CommunicationParameters used. It corresponds to the structure given as argument to the startPublishing() method. :return: CommunicationParameters containing the parameters used to initialize communication with the Fusion Module. ### `set_svo_position(self, position) -> ERROR_CODE` Sets the playback cursor to the desired position in the SVO file. This method allows you to move around within a played-back SVO file. After calling, the next call to grab() will read the provided position. :param position: The position in the SVO file. :return: An error code stating the success, or not. **Note:** The method works only if the camera is open in SVO playback mode. import pyzed.sl as sl def main(): # Create a ZED camera object zed = sl.Camera() # Set configuration parameters init_params = sl.InitParameters() init_params.set_from_svo_file("path/to/my/file.svo") # Open the camera err = zed.open(init_params) if err != sl.ERROR_CODE.SUCCESS: print(repr(err)) exit(-1) # Loop between frames 0 and 50 left_image = sl.Mat() while zed.get_svo_position() < zed.get_svo_number_of_frames() - 1: print("Current frame: ", zed.get_svo_position()) # Loop if we reached frame 50 if zed.get_svo_position() == 50: err = zed.set_svo_position(0) if err != sl.ERROR_CODE.SUCCESS: print(repr(err)) exit(-1) # Grab an image if zed.grab() == sl.ERROR_CODE.SUCCESS: zed.retrieve_image(left_image, sl.VIEW.LEFT) # Get the rectified left image # Use the image in your application # Close the Camera zed.close() return 0 if __name__ == "__main__" : main() ### `pause_svo_reading(self, status) -> None` Pauses or resumes SVO reading when using SVO Real time mode :param status: If true, the reading is paused. If false, the reading is resumed. **Note:** This is only relevant for SVO InitParameters::svo_real_time_mode ### `get_svo_position(self) -> int` Returns the current playback position in the SVO file. The position corresponds to the number of frames already read from the SVO file, starting from 0 to n. Each grab() call increases this value by one (except when using InitParameters.svo_real_time_mode). :return: The current frame position in the SVO file. -1 if the SDK is not reading an SVO. **Note:** The method works only if the camera is open in SVO playback mode. See set_svo_position() for an example. ### `get_svo_number_of_frames(self) -> int` Returns the number of frames in the SVO file. :return: The total number of frames in the SVO file. -1 if the SDK is not reading a SVO. The method works only if the camera is open in SVO playback mode. ### `ingest_data_into_svo(self, data) -> ERROR_CODE` ingest a SVOData in the SVO file. :return: An error code stating the success, or not. The method works only if the camera is open in SVO recording mode. ### `get_svo_data_keys(self) -> list` Get the external channels that can be retrieved from the SVO file. :return: a list of keys The method works only if the camera is open in SVO playback mode. ### `retrieve_svo_data(self, key, data, ts_begin, ts_end) -> ERROR_CODE` retrieve SVO datas from the SVO file at the given channel key and in the given timestamp range. :return: An error code stating the success, or not. :param key: The channel key. :param data: The dict to be filled with SVOData objects, with timestamps as keys. :param ts_begin: The beginning of the range. :param ts_end: The end of the range. The method works only if the camera is open in SVO playback mode. ### `set_camera_settings(self, settings: VIDEO_SETTINGS, value=-1) -> ERROR_CODE` Sets the value of the requested VIDEO_SETTINGS "camera setting" (gain, brightness, hue, exposure, etc.). This method only applies for VIDEO_SETTINGS that require a single value. Possible values (range) of each settings are available here. :param settings: The setting to be set. :param value: The value to set. Default: auto mode :return: ERROR_CODE to indicate if the method was successful. **Warning:** Setting VIDEO_SETTINGS.EXPOSURE or VIDEO_SETTINGS.GAIN to default will automatically sets the other to default. **Note:** The method works only if the camera is open in LIVE or STREAM mode. # Set the gain to 50 zed.set_camera_settings(sl.VIDEO_SETTINGS.GAIN, 50) ### `set_camera_settings_range(self, settings: VIDEO_SETTINGS, mini=-1, maxi=-1) -> ERROR_CODE` Sets the value of the requested VIDEO_SETTINGS "camera setting" that supports two values (min/max). This method only works with the following VIDEO_SETTINGS: - sl.VIDEO_SETTINGS.AUTO_EXPOSURE_TIME_RANGE - sl.VIDEO_SETTINGS.AUTO_ANALOG_GAIN_RANGE - sl.VIDEO_SETTINGS.AUTO_DIGITAL_GAIN_RANGE :param settings: The setting to be set. :param min: The minimum value that can be reached (-1 or 0 gives full range). :param max: The maximum value that can be reached (-1 or 0 gives full range). :return: ERROR_CODE to indicate if the method was successful. **Warning:** If VIDEO_SETTINGS settings is not supported or min >= max, it will return ERROR_CODE.INVALID_FUNCTION_PARAMETERS. **Note:** The method works only if the camera is open in LIVE or STREAM mode. # For ZED X based product, set the automatic exposure from 2ms to 5ms. Expected exposure time cannot go beyond those values zed.set_camera_settings_range(sl.VIDEO_SETTINGS.AEC_RANGE, 2000, 5000); ### `set_camera_settings_roi(self, settings: VIDEO_SETTINGS, roi, eye: SIDE=SIDE.BOTH, reset=False) -> ERROR_CODE` Overloaded method for VIDEO_SETTINGS.AEC_AGC_ROI which takes a Rect as parameter. :param settings: Must be set at VIDEO_SETTINGS.AEC_AGC_ROI, otherwise the method will have no impact. :param roi: Rect that defines the target to be applied for AEC/AGC computation. Must be given according to camera resolution. :param eye: SIDE on which to be applied for AEC/AGC computation. Default: SIDE.BOTH :param reset: Cancel the manual ROI and reset it to the full image. Default: False **Note:** The method works only if the camera is open in LIVE or STREAM mode. roi = sl.Rect(42, 56, 120, 15) zed.set_camera_settings_roi(sl.VIDEO_SETTINGS.AEC_AGC_ROI, roi, sl.SIDE.BOTH) ### `get_camera_settings(self, setting: VIDEO_SETTINGS) -> tuple[ERROR_CODE, int]` Returns the current value of the requested VIDEO_SETTINGS "camera setting" (gain, brightness, hue, exposure, etc.). Possible values (range) of each setting are available here. :param setting: The requested setting. :return: ERROR_CODE to indicate if the method was successful. :return: The current value for the corresponding setting. err, gain = zed.get_camera_settings(sl.VIDEO_SETTINGS.GAIN) if err == sl.ERROR_CODE.SUCCESS: print("Current gain value:", gain) else: print("error:", err) **Note:** The method works only if the camera is open in LIVE or STREAM mode. **Note:** Settings are not exported in the SVO file format. ### `get_camera_settings_range(self, setting: VIDEO_SETTINGS) -> tuple[ERROR_CODE, int, int]` Returns the values of the requested settings for VIDEO_SETTINGS that supports two values (min/max). This method only works with the following VIDEO_SETTINGS: - sl.VIDEO_SETTINGS.AUTO_EXPOSURE_TIME_RANGE - sl.VIDEO_SETTINGS.AUTO_ANALOG_GAIN_RANGE - sl.VIDEO_SETTINGS.AUTO_DIGITAL_GAIN_RANGE Possible values (range) of each setting are available here. :param setting: The requested setting. :return: ERROR_CODE to indicate if the method was successful. :return: The current value of the minimum for the corresponding setting. :return: The current value of the maximum for the corresponding setting. err, aec_range_min, aec_range_max = zed.get_camera_settings(sl.VIDEO_SETTINGS.AUTO_EXPOSURE_TIME_RANGE) if err == sl.ERROR_CODE.SUCCESS: print("Current AUTO_EXPOSURE_TIME_RANGE range values ==> min:", aec_range_min, "max:", aec_range_max) else: print("error:", err) **Note:** Works only with ZED X that supports low-level controls ### `get_camera_settings_roi(self, setting: VIDEO_SETTINGS, roi, eye: SIDE=SIDE.BOTH) -> ERROR_CODE` Returns the current value of the currently used ROI for the camera setting AEC_AGC_ROI. :param setting: Must be set at VIDEO_SETTINGS.AEC_AGC_ROI, otherwise the method will have no impact. (Direction: in) :param roi: Roi that will be filled. (Direction: out) :param eye: The requested side. Default: SIDE.BOTH (Direction: in) :return: ERROR_CODE to indicate if the method was successful. roi = sl.Rect() err = zed.get_camera_settings_roi(sl.VIDEO_SETTINGS.AEC_AGC_ROI, roi, sl.SIDE.BOTH) print("Current ROI for AEC_AGC: " + str(roi.x) + " " + str(roi.y)+ " " + str(roi.width) + " " + str(roi.height)) **Note:** Works only if the camera is open in LIVE or STREAM mode with VIDEO_SETTINGS.AEC_AGC_ROI. **Note:** It will return ERROR_CODE.INVALID_FUNCTION_CALL or ERROR_CODE.INVALID_FUNCTION_PARAMETERS otherwise. ### `is_camera_setting_supported(self, setting: VIDEO_SETTINGS) -> bool` Returns if the video setting is supported by the camera or not :param setting: the video setting to test (Direction: in) :return: True if the VIDEO_SETTINGS is supported by the camera, False otherwise ### `get_current_fps(self) -> float` Returns the current framerate at which the grab() method is successfully called. The returned value is based on the difference of camera get_timestamp() "timestamps" between two successful grab() calls. :return: The current SDK framerate **Warning:** The returned framerate (number of images grabbed per second) can be lower than InitParameters.camera_fps if the grab() function runs slower than the image stream or is called too often. current_fps = zed.get_current_fps() print("Current framerate: ", current_fps) ### `get_timestamp(self, time_reference: TIME_REFERENCE) -> Timestamp` Returns the timestamp in the requested TIME_REFERENCE. - When requesting the TIME_REFERENCE.IMAGE timestamp, the UNIX nanosecond timestamp of the latest grab() "grabbed" image will be returned. This value corresponds to the time at which the entire image was available in the PC memory. As such, it ignores the communication time that corresponds to 2 or 3 frame-time based on the fps (ex: 33.3ms to 50ms at 60fps). - When requesting the TIME_REFERENCE.CURRENT timestamp, the current UNIX nanosecond timestamp is returned. This function can also be used when playing back an SVO file. :param time_reference: The selected TIME_REFERENCE. :return: The Timestamp in nanosecond. 0 if not available (SVO file without compression). **Note:** As this function returns UNIX timestamps, the reference it uses is common across several Camera instances. This can help to organized the grabbed images in a multi-camera application. last_image_timestamp = zed.get_timestamp(sl.TIME_REFERENCE.IMAGE) current_timestamp = zed.get_timestamp(sl.TIME_REFERENCE.CURRENT) print("Latest image timestamp: ", last_image_timestamp.get_nanoseconds(), "ns from Epoch.") print("Current timestamp: ", current_timestamp.get_nanoseconds(), "ns from Epoch.") ### `get_frame_dropped_count(self) -> int` Returns the number of frames dropped since grab() was called for the first time. A dropped frame corresponds to a frame that never made it to the grab method. This can happen if two frames were extracted from the camera when grab() is called. The older frame will be dropped so as to always use the latest (which minimizes latency). :return: The number of frames dropped since the first grab() call. ### `get_current_min_max_depth(self) -> tuple[ERROR_CODE, float, float]` Gets the current range of perceived depth. :param min: Minimum depth detected (in selected sl.UNIT). (Direction: out) :param max: Maximum depth detected (in selected sl.UNIT). (Direction: out) :return: ERROR_CODE.SUCCESS if values can be extracted, ERROR_CODE.FAILURE otherwise. ### `get_camera_information(self, resizer=None) -> CameraInformation` Returns the CameraInformation associated the camera being used. To ensure accurate calibration, it is possible to specify a custom resolution as a parameter when obtaining scaled information, as calibration parameters are resolution-dependent. When reading an SVO file, the parameters will correspond to the camera used for recording. :param resizer: You can specify a size different from the default image size to get the scaled camera information. Default = (0,0) meaning original image size (given by CameraConfiguration.resolution "get_camera_information().camera_configuration.resolution"). :return: CameraInformation containing the calibration parameters of the ZED, as well as serial number and firmware version. **Warning:** The returned parameters might vary between two execution due to the InitParameters.camera_disable_self_calib "self-calibration" being run in the open() method. **Note:** The calibration file SNXXXX.conf can be found in: - **Windows:** C:/ProgramData/Stereolabs/settings/ - **Linux:** /usr/local/zed/settings/ ### `get_runtime_parameters(self) -> RuntimeParameters` Returns the RuntimeParameters used. It corresponds to the structure given as argument to the grab() method. :return: RuntimeParameters containing the parameters that define the behavior of the grab method. ### `get_init_parameters(self) -> InitParameters` Returns the InitParameters associated with the Camera object. It corresponds to the structure given as argument to open() method. :return: InitParameters containing the parameters used to initialize the Camera object. ### `get_positional_tracking_parameters(self) -> PositionalTrackingParameters` Returns the PositionalTrackingParameters used. It corresponds to the structure given as argument to the enable_positional_tracking() method. :return: PositionalTrackingParameters containing the parameters used for positional tracking initialization. ### `get_spatial_mapping_parameters(self) -> SpatialMappingParameters` Returns the SpatialMappingParameters used. It corresponds to the structure given as argument to the enable_spatial_mapping() method. :return: SpatialMappingParameters containing the parameters used for spatial mapping initialization. ### `get_object_detection_parameters(self, instance_module_id=0) -> ObjectDetectionParameters` Returns the ObjectDetectionParameters used. It corresponds to the structure given as argument to the enable_object_detection() method. :return: ObjectDetectionParameters containing the parameters used for object detection initialization. ### `get_body_tracking_parameters(self, instance_id=0) -> BodyTrackingParameters` Returns the BodyTrackingParameters used. It corresponds to the structure given as argument to the enable_body_tracking() method. :return: BodyTrackingParameters containing the parameters used for body tracking initialization. ### `get_streaming_parameters(self) -> StreamingParameters` Returns the StreamingParameters used. It corresponds to the structure given as argument to the enable_streaming() method. :return: StreamingParameters containing the parameters used for streaming initialization. ### `enable_positional_tracking(self, py_tracking=None) -> ERROR_CODE` Initializes and starts the positional tracking processes. This method allows you to enable the position estimation of the SDK. It only has to be called once in the camera's lifetime. When enabled, the position will be update at each grab() call. Tracking-specific parameters can be set by providing PositionalTrackingParameters to this method. :param py_tracking: A structure containing all the specific parameters for the positional tracking. Default: a preset of PositionalTrackingParameters. :return: ERROR_CODE.FAILURE if the PositionalTrackingParameters.area_file_path file wasn't found, ERROR_CODE.SUCCESS otherwise. **Warning:** The positional tracking feature benefits from a high framerate. We found HD720@60fps to be the best compromise between image quality and framerate. import pyzed.sl as sl def main() : # --- Initialize a Camera object and open the ZED # Create a ZED camera object zed = sl.Camera() # Set configuration parameters init_params = sl.InitParameters() init_params.camera_resolution = sl.RESOLUTION.HD720 # Use HD720 video mode init_params.camera_fps = 60 # Set fps at 60 # Open the camera err = zed.open(init_params) if err != sl.ERROR_CODE.SUCCESS: print(repr(err)) exit(-1) # Set tracking parameters track_params = sl.PositionalTrackingParameters() # Enable positional tracking err = zed.enable_positional_tracking(track_params) if err != sl.ERROR_CODE.SUCCESS: print("Tracking error: ", repr(err)) exit(-1) # --- Main loop while True: if zed.grab() == sl.ERROR_CODE.SUCCESS: # Grab an image and computes the tracking camera_pose = sl.Pose() zed.get_position(camera_pose, sl.REFERENCE_FRAME.WORLD) translation = camera_pose.get_translation().get() print("Camera position: X=", translation[0], " Y=", translation[1], " Z=", translation[2]) # --- Close the Camera zed.close() return 0 if __name__ == "__main__" : main() ### `update_self_calibration(self) -> None` Performs a new self-calibration process. In some cases, due to temperature changes or strong vibrations, the stereo calibration becomes less accurate. Use this method to update the self-calibration data and get more reliable depth values. **Note:** The self-calibration will occur at the next grab() call. **Note:** This method is similar to the previous reset_self_calibration() used in 2.X SDK versions. **Warning:** New values will then be available in get_camera_information(), be sure to get them to still have consistent 2D <-> 3D conversion. ### `enable_body_tracking(self, body_tracking_parameters=None) -> ERROR_CODE` Initializes and starts the body tracking module. The body tracking module currently supports multiple classes of human skeleton detection with the BODY_TRACKING_MODEL.HUMAN_BODY_FAST, BODY_TRACKING_MODEL "BODY_TRACKING_MODEL::HUMAN_BODY_MEDIUM" or BODY_TRACKING_MODEL "BODY_TRACKING_MODEL::HUMAN_BODY_ACCURATE". This model only detects humans but provides a full skeleton map for each person. Detected objects can be retrieved using the retrieve_bodies() method. **Note:** - **This Deep Learning detection module is not available for MODEL.ZED cameras (first generation ZED cameras).** **Note:** - This feature uses AI to locate objects and requires a powerful GPU. A GPU with at least 3GB of memory is recommended. :param body_tracking_parameters: A structure containing all the specific parameters for the object detection. Default: a preset of BodyTrackingParameters. :return: ERROR_CODE.SUCCESS if everything went fine. :return: ERROR_CODE.OBJECT_DETECTION_NOT_AVAILABLE if the AI model is missing or corrupted. In this case, the SDK needs to be reinstalled :return: ERROR_CODE.OBJECT_DETECTION_MODULE_NOT_COMPATIBLE_WITH_CAMERA if the camera used does not have an IMU (MODEL.ZED). :return: ERROR_CODE.SENSORS_NOT_DETECTED if the camera model is correct (not MODEL.ZED) but the IMU is missing. It probably happens because InitParameters.sensors_required was set to False and that IMU has not been found. :return: ERROR_CODE.INVALID_FUNCTION_CALL if one of the **body_tracking_parameters** parameter is not compatible with other modules parameters (for example, **depth_mode** has been set to DEPTH_MODE.NONE). :return: ERROR_CODE.FAILURE otherwise. import pyzed.sl as sl def main() : # Create a ZED camera object zed = sl.Camera() # Open the camera err = zed.open() if err != sl.ERROR_CODE.SUCCESS: print("Opening camera error:", repr(err)) exit(-1) # Enable position tracking (mandatory for object detection) tracking_params = sl.PositionalTrackingParameters() err = zed.enable_positional_tracking(tracking_params) if err != sl.ERROR_CODE.SUCCESS: print("Enabling Positional Tracking error:", repr(err)) exit(-1) # Set the body tracking parameters body_tracking_params = sl.BodyTrackingParameters() # Enable the body tracking err = zed.enable_body_tracking(body_tracking_params) if err != sl.ERROR_CODE.SUCCESS: print("Enabling Body Tracking error:", repr(err)) exit(-1) # Grab an image and detect bodies on it bodies = sl.Bodies() while True : if zed.grab() == sl.ERROR_CODE.SUCCESS: zed.retrieve_bodies(bodies) print(len(bodies.body_list), "bodies detected") # Use the bodies in your application # Close the camera zed.disable_body_tracking() zed.close() if __name__ == "__main__": main() ### `disable_body_tracking(self, instance_id=0, force_disable_all_instances=False) -> None` Disables the body tracking process. The body tracking module immediately stops and frees its memory allocations. :param instance_id: Id of the body tracking instance. Used when multiple instances of the body tracking module are enabled at the same time. :param force_disable_all_instances: Should disable all instances of the body tracking module or just **instance_module_id**. **Note:** If the body tracking has been enabled, this method will automatically be called by close(). ### `retrieve_bodies(self, bodies, body_tracking_runtime_parameters=None, instance_id=0) -> ERROR_CODE` Retrieves body tracking data from the body tracking module. This method returns the result of the body tracking, whether the module is running synchronously or asynchronously. - **Asynchronous:** this method immediately returns the last bodies tracked. If the current tracking isn't done, the bodies from the last tracking will be returned, and Bodies.is_new will be set to False. - **Synchronous:** this method executes tracking and waits for it to finish before returning the detected objects. It is recommended to keep the same Bodies object as the input of all calls to this method. This will enable the identification and the tracking of every detected object. :param bodies: The detected bodies will be saved into this object. If the object already contains data from a previous tracking, it will be updated, keeping a unique ID for the same person. :param body_tracking_runtime_parameters: Body tracking runtime settings, can be changed at each tracking. In async mode, the parameters update is applied on the next iteration. If None, the previously used parameters will be used. :param instance_id: Id of the body tracking instance. Used when multiple instances of the body tracking module are enabled at the same time. :return: ERROR_CODE.SUCCESS if everything went fine, ERROR_CODE.FAILURE otherwise. bodies = sl.Bodies() # Unique Bodies to be updated after each grab # Main loop while True: if zed.grab() == sl.ERROR_CODE.SUCCESS: # Grab an image from the camera zed.retrieve_bodies(bodies) print(len(bodies.body_list), "bodies detected") ### `set_body_tracking_runtime_parameters(self, body_tracking_runtime_parameters, instance_module_id=0) -> ERROR_CODE` Set the body tracking runtime parameters ### `is_body_tracking_enabled(self, instance_id=0) -> bool` Tells if the body tracking module is enabled. ### `get_sensors_data(self, py_sensor_data, time_reference=TIME_REFERENCE.CURRENT) -> ERROR_CODE` Retrieves the SensorsData (IMU, magnetometer, barometer) at a specific time reference. - Calling get_sensors_data with TIME_REFERENCE.CURRENT gives you the latest sensors data received. Getting all the data requires to call this method at 800Hz in a thread. - Calling get_sensors_data with TIME_REFERENCE.IMAGE gives you the sensors data at the time of the latest image grab() "grabbed". SensorsData object contains the previous IMUData structure that was used in ZED SDK v2.X: For IMU data, the values are provided in 2 ways :
  • **Time-fused** pose estimation that can be accessed using: * IMUData.get_pose "data.get_imu_data().get_pose()"
  • **Raw values** from the IMU sensor: * IMUData.get_angular_velocity "data.get_imu_data().get_angular_velocity()", corresponding to the gyroscope * IMUData.get_linear_acceleration "data.get_imu_data().get_linear_acceleration()", corresponding to the accelerometer both the gyroscope and accelerometer are synchronized.
  • The delta time between previous and current values can be calculated using data.imu.timestamp **Note:** The IMU quaternion (fused data) is given in the specified COORDINATE_SYSTEM of InitParameters. :param py_sensor_data: The SensorsData variable to store the data. (Direction: out) :param time_reference: Defines the reference from which you want the data to be expressed. Default: REFERENCE_FRAME.WORLD. (Direction: in) :return: ERROR_CODE.SUCCESS if sensors data have been extracted. :return: ERROR_CODE.SENSORS_NOT_AVAILABLE if the camera model is a MODEL.ZED. :return: ERROR_CODE.MOTION_SENSORS_REQUIRED if the camera model is correct but the sensors module is not opened. :return: ERROR_CODE.INVALID_FUNCTION_PARAMETERS if the **reference_time** is not valid. See Warning. **Warning:** In SVO reading mode, the TIME_REFERENCE.CURRENT is currently not available (yielding ERROR_CODE.INVALID_FUNCTION_PARAMETERS. **Warning:** Only the quaternion data and barometer data (if available) at TIME_REFERENCE.IMAGE are available. Other values will be set to 0. ### `get_sensors_data_batch(self, py_sensor_data) -> ERROR_CODE` Retrieves all SensorsData associated to most recent grabbed frame in the specified COORDINATE_SYSTEM of InitParameters. For IMU data, the values are provided in 2 ways:
  • **Time-fused** pose estimation that can be accessed using: * IMUData.get_pose "data.get_imu_data().get_pose()"
  • **Raw values** from the IMU sensor: * IMUData.get_angular_velocity "data.get_imu_data().get_angular_velocity()", corresponding to the gyroscope * IMUData.get_linear_acceleration "data.get_imu_data().get_linear_acceleration()", corresponding to the accelerometer both the gyroscope and accelerometer are synchronized.
  • The delta time between previous and current values can be calculated using data.imu.timestamp :param py_sensor_data: The SensorsData list to store the data. (Direction: out) :return: ERROR_CODE.SUCCESS if sensors data have been extracted. :return: ERROR_CODE.SENSORS_NOT_AVAILABLE if the camera model is a MODEL.ZED. :return: ERROR_CODE.MOTION_SENSORS_REQUIRED if the camera model is correct but the sensors module is not opened. :return: ERROR_CODE.INVALID_FUNCTION_PARAMETERS if the **reference_time** is not valid. See Warning. if zed.grab() == sl.ERROR_CODE.SUCCESS: sensors_data = [] if (zed.get_sensors_data_batch(sensors_data) == sl.ERROR_CODE.SUCCESS): for data in sensors_data: print("IMU data: ", data.imu.get_angular_velocity(), data.imu.get_linear_acceleration()) print("IMU pose: ", data.imu.get_pose().get_translation()) print("IMU orientation: ", data.imu.get_orientation().get()) ### `set_imu_prior(self, transfom) -> ERROR_CODE` Set an optional IMU orientation hint that will be used to assist the tracking during the next grab(). This method can be used to assist the positional tracking rotation. **Note:** This method is only effective if the camera has a model other than a MODEL.ZED, which does not contains internal sensors. **Warning:** It needs to be called before the grab() method. :param transform: Transform to be ingested into IMU fusion. Note that only the rotation is used. :return: ERROR_CODE.SUCCESS if the transform has been passed, ERROR_CODE.INVALID_FUNCTION_CALL otherwise (e.g. when used with a ZED camera which doesn't have IMU data). ### `get_position(self, py_pose, reference_frame: REFERENCE_FRAME=REFERENCE_FRAME.WORLD) -> POSITIONAL_TRACKING_STATE` Retrieves the estimated position and orientation of the camera in the specified REFERENCE_FRAME "reference frame". - Using REFERENCE_FRAME.WORLD, the returned pose relates to the initial position of the camera (PositionalTrackingParameters.initial_world_transform ). - Using REFERENCE_FRAME.CAMERA, the returned pose relates to the previous position of the camera. If the tracking has been initialized with PositionalTrackingParameters.enable_area_memory to True (default), this method can return POSITIONAL_TRACKING_STATE.SEARCHING. This means that the tracking lost its link to the initial referential and is currently trying to relocate the camera. However, it will keep on providing position estimations. :param camera_pose: The pose containing the position of the camera and other information (timestamp, confidence). (Direction: out) :param reference_frame: Defines the reference from which you want the pose to be expressed. Default: REFERENCE_FRAME.WORLD. (Direction: in) :return: The current state of the tracking process. **Note:** Extract Rotation Matrix: Pose.get_rotation_matrix() **Note:** Extract Translation Vector: Pose.get_translation() **Note:** Extract Orientation / Quaternion: Pose.get_orientation() **Warning:** This method requires the tracking to be enabled. enablePositionalTracking() . **Note:** The position is provided in the InitParameters.coordinate_system . See COORDINATE_SYSTEM for its physical origin. while True: if zed.grab() == sl.ERROR_CODE.SUCCESS: # Grab an image and computes the tracking camera_pose = sl.Pose() zed.get_position(camera_pose, sl.REFERENCE_FRAME.WORLD) translation = camera_pose.get_translation().get() print("Camera position: X=", translation[0], " Y=", translation[1], " Z=", translation[2]) print("Camera Euler rotation: X=", camera_pose.get_euler_angles()[0], " Y=", camera_pose.get_euler_angles()[1], " Z=", camera_pose.get_euler_angles()[2]) print("Camera Rodrigues rotation: X=", camera_pose.get_rotation_vector()[0], " Y=", camera_pose.get_rotation_vector()[1], " Z=", camera_pose.get_rotation_vector()[2]) orientation = camera_pose.get_orientation().get() print("Camera quaternion orientation: X=", orientation[0], " Y=", orientation[1], " Z=", orientation[2], " W=", orientation[3]) ### `get_positional_tracking_landmarks(self, landmarks) -> ERROR_CODE` Get the current positional tracking landmarks. :param landmarks: The dictionary of landmarks_id and landmark. :return: ERROR_CODE that indicate if the function succeed or not. ### `get_positional_tracking_landmarks2d(self, landmark2d) -> ERROR_CODE` Get the current positional tracking landmark. :param landmark: The landmark. :return: ERROR_CODE that indicate if the function succeed or not. ### `get_positional_tracking_keyframes(self, keyframes) -> ERROR_CODE` Get the Keyframe currenlty used by the positional tracking. :param keyframes: The dictionary of keyframes_id and keyframe. :return: ERROR_CODE that indicate if the function succeed or not. ### `get_positional_tracking_status(self) -> PositionalTrackingStatus` Return the current status of positional tracking module. :return: sl::PositionalTrackingStatus current status of positional tracking module. ### `get_area_export_state(self) -> AREA_EXPORTING_STATE` Returns the state of the spatial memory export process. As Camera.save_area_map() only starts the exportation, this method allows you to know when the exportation finished or if it failed. :return: The current state of the spatial memory export process. ### `save_area_map(self, area_file_path='') -> ERROR_CODE` Saves the current area learning file. The file will contain spatial memory data generated by the tracking. If the tracking has been initialized with PositionalTrackingParameters.enable_area_memory to True (default), the method allows you to export the spatial memory. Reloading the exported file in a future session with PositionalTrackingParameters.area_file_path initializes the tracking within the same referential. This method is asynchronous, and only triggers the file generation. You can use get_area_export_state() to get the export state. The positional tracking keeps running while exporting. :param area_file_path: Path of an '.area' file to save the spatial memory database in. :return: ERROR_CODE.FAILURE if the **area_file_path** file wasn't found, ERROR_CODE.SUCCESS otherwise. See get_area_export_state() **Note:** Please note that this method will also flush the area database that was built/loaded. **Warning:** If the camera wasn't moved during the tracking session, or not enough, the spatial memory won't be usable and the file won't be exported. **Warning:** The get_area_export_state() will return AREA_EXPORTING_STATE.FILE_EMPTY. **Warning:** A few meters (~3m) of translation or a full rotation should be enough to get usable spatial memory. **Warning:** However, as it should be used for relocation purposes, visiting a significant portion of the environment is recommended before exporting. while True : if zed.grab() == sl.ERROR_CODE.SUCCESS: # Grab an image and computes the tracking camera_pose = Pose() zed.get_position(camera_pose, REFERENCE_FRAME.WORLD) # Export the spatial memory for future sessions zed.save_area_map("office.area") # The actual file will be created asynchronously. print(repr(zed.get_area_export_state())) # Close the camera zed.close() ### `disable_positional_tracking(self, area_file_path='') -> None` Disables the positional tracking. The positional tracking is immediately stopped. If a file path is given, save_area_map() will be called asynchronously. See get_area_export_state() to get the exportation state. If the tracking has been enabled, this function will automatically be called by close() . :param area_file_path: If set, saves the spatial memory into an '.area' file. Default: (empty) **area_file_path** is the name and path of the database, e.g. path/to/file/myArea1.area". ### `is_positional_tracking_enabled(self) -> bool` Tells if the tracking module is enabled ### `reset_positional_tracking(self, path) -> ERROR_CODE` Resets the tracking, and re-initializes the position with the given transformation matrix. :param path: Position of the camera in the world frame when the method is called. :return: ERROR_CODE.SUCCESS if the tracking has been reset, ERROR_CODE.FAILURE otherwise. **Note:** Please note that this method will also flush the accumulated or loaded spatial memory. ### `enable_spatial_mapping(self, py_spatial=None) -> ERROR_CODE` Initializes and starts the spatial mapping processes. The spatial mapping will create a geometric representation of the scene based on both tracking data and 3D point clouds. The resulting output can be a Mesh or a FusedPointCloud. It can be be obtained by calling extract_whole_spatial_map() or retrieve_spatial_map_async(). Note that retrieve_spatial_map_async should be called after request_spatial_map_async(). :param py_spatial: A structure containing all the specific parameters for the spatial mapping. Default: a balanced parameter preset between geometric fidelity and output file size. For more information, see the SpatialMappingParameters documentation. :return: ERROR_CODE.SUCCESS if everything went fine, ERROR_CODE.FAILURE otherwise. **Warning:** The tracking (enable_positional_tracking() ) and the depth (RuntimeParameters.enable_depth ) needs to be enabled to use the spatial mapping. **Warning:** The performance greatly depends on the **py_spatial**. **Warning:** Lower SpatialMappingParameters.range_meter and SpatialMappingParameters.resolution_meter for higher performance. If the mapping framerate is too slow in live mode, consider using an SVO file, or choose a lower mesh resolution. **Note:** This feature uses host memory (RAM) to store the 3D map. The maximum amount of available memory allowed can be tweaked using the SpatialMappingParameters. Exceeding the maximum memory allowed immediately stops the mapping. import pyzed.sl as sl def main() : # Create a ZED camera object zed = sl.Camera() # Set initial parameters init_params = sl.InitParameters() init_params.camera_resolution = sl.RESOLUTION.HD720 # Use HD720 video mode (default fps: 60) init_params.coordinate_system = sl.COORDINATE_SYSTEM.RIGHT_HANDED_Y_UP # Use a right-handed Y-up coordinate system (The OpenGL one) init_params.coordinate_units = sl.UNIT.METER # Set units in meters # Open the camera err = zed.open(init_params) if err != sl.ERROR_CODE.SUCCESS: exit(-1) # Positional tracking needs to be enabled before using spatial mapping tracking_parameters = sl.PositionalTrackingParameters() err = zed.enable_positional_tracking(tracking_parameters) if err != sl.ERROR_CODE.SUCCESS: exit(-1) # Enable spatial mapping mapping_parameters = sl.SpatialMappingParameters() err = zed.enable_spatial_mapping(mapping_parameters) if err != sl.ERROR_CODE.SUCCESS: exit(-1) # Grab data during 500 frames i = 0 mesh = sl.Mesh() # Create a mesh object while i < 500 : # For each new grab, mesh data is updated if zed.grab() == sl.ERROR_CODE.SUCCESS : # In the background, the spatial mapping will use newly retrieved images, depth and pose to update the mesh mapping_state = zed.get_spatial_mapping_state() # Print spatial mapping state print("Images captured: ", i, "/ 500 || Spatial mapping state: ", repr(mapping_state)) i = i + 1 # Extract, filter and save the mesh in a .obj file print("Extracting Mesh ...") zed.extract_whole_spatial_map(mesh) # Extract the whole mesh print("Filtering Mesh ...") mesh.filter(sl.MESH_FILTER.LOW) # Filter the mesh (remove unnecessary vertices and faces) print("Saving Mesh in mesh.obj ...") mesh.save("mesh.obj") # Save the mesh in an obj file # Disable tracking and mapping and close the camera zed.disable_spatial_mapping() zed.disable_positional_tracking() zed.close() return 0 if __name__ == "__main__" : main() ### `pause_spatial_mapping(self, status) -> None` Pauses or resumes the spatial mapping processes. As spatial mapping runs asynchronously, using this method can pause its computation to free some processing power, and resume it again later. For example, it can be used to avoid mapping a specific area or to pause the mapping when the camera is static. :param status: If True, the integration is paused. If False, the spatial mapping is resumed. ### `get_spatial_mapping_state(self) -> SPATIAL_MAPPING_STATE` Returns the current spatial mapping state. As the spatial mapping runs asynchronously, this method allows you to get reported errors or status info. :return: The current state of the spatial mapping process. See also SPATIAL_MAPPING_STATE ### `request_spatial_map_async(self) -> None` Starts the spatial map generation process in a non-blocking thread from the spatial mapping process. The spatial map generation can take a long time depending on the mapping resolution and covered area. This function will trigger the generation of a mesh without blocking the program. You can get info about the current generation using get_spatial_map_request_status_async(), and retrieve the mesh using retrieve_spatial_map_async(). **Note:** Only one mesh can be generated at a time. If the previous mesh generation is not over, new calls of the function will be ignored. ### `get_spatial_map_request_status_async(self) -> ERROR_CODE` Returns the spatial map generation status. This status allows you to know if the mesh can be retrieved by calling retrieve_spatial_map_async(). :return: ERROR_CODE.SUCCESS if the mesh is ready and not yet retrieved, otherwise ERROR_CODE.FAILURE. ### `retrieve_spatial_map_async(self, py_mesh) -> ERROR_CODE` Retrieves the current generated spatial map. After calling request_spatial_map_async(), this method allows you to retrieve the generated mesh or fused point cloud. The Mesh or FusedPointCloud will only be available when get_spatial_map_request_status_async() returns ERROR_CODE.SUCCESS. :param py_mesh: The Mesh or FusedPointCloud to be filled with the generated spatial map. (Direction: out) :return: ERROR_CODE.SUCCESS if the mesh is retrieved, otherwise ERROR_CODE.FAILURE. **Note:** This method only updates the necessary chunks and adds the new ones in order to improve update speed. **Warning:** You should not modify the mesh / fused point cloud between two calls of this method, otherwise it can lead to a corrupted mesh / fused point cloud. See request_spatial_map_async() for an example. ### `extract_whole_spatial_map(self, py_mesh) -> ERROR_CODE` Extract the current spatial map from the spatial mapping process. If the object to be filled already contains a previous version of the mesh / fused point cloud, only changes will be updated, optimizing performance. :param py_mesh: The Mesh or FusedPointCloud to be filled with the generated spatial map. (Direction: out) :return: ERROR_CODE.SUCCESS if the mesh is filled and available, otherwise ERROR_CODE.FAILURE. **Warning:** This is a blocking function. You should either call it in a thread or at the end of the mapping process. The extraction can be long, calling this function in the grab loop will block the depth and tracking computation giving bad results. ### `find_plane_at_hit(self, coord, py_plane: Plane, parameters=None) -> ERROR_CODE` Checks the plane at the given left image coordinates. This method gives the 3D plane corresponding to a given pixel in the latest left image grab() "grabbed". The pixel coordinates are expected to be contained x=[0;width-1] and y=[0;height-1], where width/height are defined by the input resolution. :param coord: The image coordinate. The coordinate must be taken from the full-size image (Direction: in) :param plane: The detected plane if the method succeeded. (Direction: out) :param parameters: A structure containing all the specific parameters for the plane detection. Default: a preset of PlaneDetectionParameters. (Direction: in) :return: ERROR_CODE.SUCCESS if a plane is found otherwise ERROR_CODE.PLANE_NOT_FOUND. **Note:** The reference frame is defined by the RuntimeParameters.measure3D_reference_frame given to the grab() method. ### `find_floor_plane(self, py_plane, reset_tracking_floor_frame, floor_height_prior=float('nan'), world_orientation_prior=None, floor_height_prior_tolerance=float('nan')) -> ERROR_CODE` Detect the floor plane of the scene. This method analyses the latest image and depth to estimate the floor plane of the scene. It expects the floor plane to be visible and bigger than other candidate planes, like a table. :param py_plane: The detected floor plane if the method succeeded. (Direction: out) :param reset_tracking_floor_frame: The transform to align the tracking with the floor plane. (Direction: out) The initial position will then be at ground height, with the axis align with the gravity. The positional tracking needs to be reset/enabled with this transform as a parameter (PositionalTrackingParameters.initial_world_transform). :param floor_height_prior: Prior set to locate the floor plane depending on the known camera distance to the ground, expressed in the same unit as the ZED. (Direction: in) If the prior is too far from the detected floor plane, the method will return ERROR_CODE.PLANE_NOT_FOUND. :param world_orientation_prior: Prior set to locate the floor plane depending on the known camera orientation to the ground. (Direction: in) If the prior is too far from the detected floor plane, the method will return ERROR_CODE "ERROR_CODE.PLANE_NOT_FOUND. :param floor_height_prior_tolerance: Prior height tolerance, absolute value. (Direction: in) :return: ERROR_CODE.SUCCESS if the floor plane is found and matches the priors (if defined), otherwise ERROR_CODE.PLANE_NOT_FOUND. **Note:** The reference frame is defined by the sl.RuntimeParameters (measure3D_reference_frame) given to the grab() method. **Note:** The length unit is defined by sl.InitParameters (coordinate_units). **Note:** With the ZED, the assumption is made that the floor plane is the dominant plane in the scene. The ZED Mini uses gravity as prior. ### `disable_spatial_mapping(self) -> None` Disables the spatial mapping process. The spatial mapping is immediately stopped. If the mapping has been enabled, this method will automatically be called by close(). **Note:** This method frees the memory allocated for the spatial mapping, consequently, meshes and fused point clouds cannot be retrieved after this call. ### `enable_streaming(self, streaming_parameters=None) -> ERROR_CODE` Creates a streaming pipeline. :param streaming_parameters: A structure containing all the specific parameters for the streaming. Default: a reset of StreamingParameters . :return: ERROR_CODE.SUCCESS if the streaming was successfully started. :return: ERROR_CODE.INVALID_FUNCTION_CALL if open() was not successfully called before. :return: ERROR_CODE.FAILURE if streaming RTSP protocol was not able to start. :return: ERROR_CODE.NO_GPU_COMPATIBLE if the streaming codec is not supported (in this case, use H264 codec which is supported on all NVIDIA GPU the ZED SDK supports). import pyzed.sl as sl def main() : # Create a ZED camera object zed = sl.Camera() # Set initial parameters init_params = sl.InitParameters() init_params.camera_resolution = sl.RESOLUTION.HD720 # Use HD720 video mode (default fps: 60) # Open the camera err = zed.open(init_params) if err != sl.ERROR_CODE.SUCCESS : print(repr(err)) exit(-1) # Enable streaming stream_params = sl.StreamingParameters() stream_params.port = 30000 stream_params.bitrate = 8000 err = zed.enable_streaming(stream_params) if err != sl.ERROR_CODE.SUCCESS : print(repr(err)) exit(-1) # Grab data during 500 frames i = 0 while i < 500 : if zed.grab() == sl.ERROR_CODE.SUCCESS : i = i+1 zed.disable_streaming() zed.close() return 0 if __name__ == "__main__" : main() ### `disable_streaming(self) -> None` Disables the streaming initiated by enable_streaming(). **Note:** This method will automatically be called by close() if enable_streaming() was called. See enable_streaming() for an example. ### `is_streaming_enabled(self) -> bool` Tells if the streaming is running. :return: True if the stream is running, False otherwise. ### `enable_recording(self, record) -> ERROR_CODE` Creates an SVO file to be filled by enable_recording() and disable_recording(). SVO files are custom video files containing the un-rectified images from the camera along with some meta-data like timestamps or IMU orientation (if applicable). They can be used to simulate a live ZED and test a sequence with various SDK parameters. Depending on the application, various compression modes are available. See SVO_COMPRESSION_MODE. :param record: A structure containing all the specific parameters for the recording such as filename and compression mode. Default: a reset of RecordingParameters . :return: An ERROR_CODE that defines if the SVO file was successfully created and can be filled with images. **Warning:** This method can be called multiple times during a camera lifetime, but if **video_filename** is already existing, the file will be erased. import pyzed.sl as sl def main() : # Create a ZED camera object zed = sl.Camera() # Set initial parameters init_params = sl.InitParameters() init_params.camera_resolution = sl.RESOLUTION.HD720 # Use HD720 video mode (default fps: 60) init_params.coordinate_units = sl.UNIT.METER # Set units in meters # Open the camera err = zed.open(init_params) if (err != sl.ERROR_CODE.SUCCESS): print(repr(err)) exit(-1) # Enable video recording record_params = sl.RecordingParameters("myVideoFile.svo") err = zed.enable_recording(record_params) if (err != sl.ERROR_CODE.SUCCESS): print(repr(err)) exit(-1) # Grab data during 500 frames i = 0 while i < 500 : # Grab a new frame if zed.grab() == sl.ERROR_CODE.SUCCESS: # Record the grabbed frame in the video file i = i + 1 zed.disable_recording() print("Video has been saved ...") zed.close() return 0 if __name__ == "__main__" : main() ### `disable_recording(self) -> None` Disables the recording initiated by enable_recording() and closes the generated file. **Note:** This method will automatically be called by close() if enable_recording() was called. See enable_recording() for an example. ### `get_recording_status(self) -> RecordingStatus` Get the recording information. :return: The recording state structure. For more details, see RecordingStatus. ### `pause_recording(self, value=True) -> None` Pauses or resumes the recording. :param status: If True, the recording is paused. If False, the recording is resumed. ### `get_recording_parameters(self) -> RecordingParameters` Returns the RecordingParameters used. It corresponds to the structure given as argument to the enable_recording() method. :return: RecordingParameters containing the parameters used for recording initialization. ### `get_health_status(self) -> HealthStatus` Get the Health information. :return: The health state structure. For more details, see HealthStatus. ### `get_retrieve_image_resolution(self, resolution=None) -> Resolution` Returns the resolution of the image that would be retrieved with the given resolution setting. :param resolution: The requested resolution setting. Default: Resolution(0,0) for full resolution. :return: The actual resolution of the image that would be retrieved. ### `get_retrieve_measure_resolution(self, resolution=None) -> Resolution` Returns the resolution of the measure that would be retrieved with the given resolution setting. :param resolution: The requested resolution setting. Default: Resolution(-1,-1) for full resolution. :return: The actual resolution of the measure that would be retrieved. ### `enable_object_detection(self, object_detection_parameters=None) -> ERROR_CODE` Initializes and starts object detection module. The object detection module currently support multiple StereoLabs' model for different purposes: "MULTI_CLASS", "PERSON_HEAD" The full list of model is available through OBJECT_DETECTION_MODEL and the full list of detectable objects is available through OBJECT_CLASS and OBJECT_SUBCLASS. Detected objects can be retrieved using the retrieve_objects() method. Alternatively, the object detection module supports custom class of objects with the OBJECT_DETECTION_MODEL.CUSTOM_BOX_OBJECTS (see ingestCustomBoxObjects or ingestCustomMaskObjects) or OBJECT_DETECTION_MODEL.CUSTOM_YOLOLIKE_BOX_OBJECTS (see ObjectDetectionParameters.custom_onnx_file). Detected custom objects can be retrieved using the retrieve_custom_objects() method. **Note:** - **This Depth Learning detection module is not available MODEL.ZED cameras.** **Note:** - This feature uses AI to locate objects and requires a powerful GPU. A GPU with at least 3GB of memory is recommended. :param object_detection_parameters: A structure containing all the specific parameters for the object detection. Default: a preset of ObjectDetectionParameters. :return: ERROR_CODE.SUCCESS if everything went fine. :return: ERROR_CODE.OBJECT_DETECTION_NOT_AVAILABLE if the AI model is missing or corrupted. In this case, the SDK needs to be reinstalled :return: ERROR_CODE.OBJECT_DETECTION_MODULE_NOT_COMPATIBLE_WITH_CAMERA if the camera used does not have an IMU (MODEL.ZED). :return: ERROR_CODE.SENSORS_NOT_DETECTED if the camera model is correct (not MODEL.ZED) but the IMU is missing. It probably happens because InitParameters.sensors_required was set to False and that IMU has not been found. :return: ERROR_CODE.INVALID_FUNCTION_CALL if one of the **object_detection_parameters** parameter is not compatible with other modules parameters (for example, **depth_mode** has been set to DEPTH_MODE.NONE). :return: ERROR_CODE.FAILURE otherwise. **Note:** The IMU gives the gravity vector that helps in the 3D box localization. Therefore the object detection module is not available for the MODEL.ZED models. import pyzed.sl as sl def main(): # Create a ZED camera object zed = sl.Camera() # Open the camera err = zed.open() if err != sl.ERROR_CODE.SUCCESS: print("Opening camera error:", repr(err)) exit(-1) # Enable position tracking (mandatory for object detection) tracking_params = sl.PositionalTrackingParameters() err = zed.enable_positional_tracking(tracking_params) if err != sl.ERROR_CODE.SUCCESS: print("Enabling Positional Tracking error:", repr(err)) exit(-1) # Set the object detection parameters object_detection_params = sl.ObjectDetectionParameters() # Enable the object detection err = zed.enable_object_detection(object_detection_params) if err != sl.ERROR_CODE.SUCCESS: print("Enabling Object Detection error:", repr(err)) exit(-1) # Grab an image and detect objects on it objects = sl.Objects() while True: if zed.grab() == sl.ERROR_CODE.SUCCESS: zed.retrieve_objects(objects) print(len(objects.object_list), "objects detected") # Use the objects in your application # Close the camera zed.disable_object_detection() zed.close() if __name__ == "__main__": main() ### `disable_object_detection(self, instance_module_id=0, force_disable_all_instances=False) -> None` Disables the object detection process. The object detection module immediately stops and frees its memory allocations. :param instance_module_id: Id of the object detection instance. Used when multiple instances of the object detection module are enabled at the same time. :param force_disable_all_instances: Should disable all instances of the object detection module or just **instance_module_id**. **Note:** If the object detection has been enabled, this method will automatically be called by close(). ### `set_object_detection_runtime_parameters(self, object_detection_parameters, instance_module_id=0) -> ERROR_CODE` Set the object detection runtime parameters ### `set_custom_object_detection_runtime_parameters(self, custom_object_detection_parameters, instance_module_id=0) -> ERROR_CODE` Set the custom object detection runtime parameters ### `retrieve_objects(self, py_objects, py_object_detection_parameters=None, instance_module_id=0) -> ERROR_CODE` Retrieve objects detected by the object detection module. This method returns the result of the object detection, whether the module is running synchronously or asynchronously. - **Asynchronous:** this method immediately returns the last objects detected. If the current detection isn't done, the objects from the last detection will be returned, and Objects.is_new will be set to False. - **Synchronous:** this method executes detection and waits for it to finish before returning the detected objects. It is recommended to keep the same Objects object as the input of all calls to this method. This will enable the identification and tracking of every object detected. :param py_objects: The detected objects will be saved into this object. If the object already contains data from a previous detection, it will be updated, keeping a unique ID for the same person. (Direction: out) :param py_object_detection_parameters: Object detection runtime settings, can be changed at each detection. In async mode, the parameters update is applied on the next iteration. If None, use the previously passed parameters. (Direction: in) :param instance_module_id: Id of the object detection instance. Used when multiple instances of the object detection module are enabled at the same time. :return: ERROR_CODE.SUCCESS if everything went fine, ERROR_CODE.FAILURE otherwise. objects = sl.Objects() while True: if zed.grab() == sl.ERROR_CODE.SUCCESS: zed.retrieve_objects(objects) object_list = objects.object_list for i in range(len(object_list)): print(repr(object_list[i].label)) ### `retrieve_custom_objects(self, py_objects, custom_object_detection_parameters=None, instance_module_id=0) -> ERROR_CODE` Retrieve custom objects detected by the object detection module. If the object detection module is initialized with OBJECT_DETECTION_MODEL.CUSTOM_BOX_OBJECTS, the objects retrieved will be the ones from ingest_custom_box_objects or ingest_custom_mask_objects. If the object detection module is initialized with OBJECT_DETECTION_MODEL.CUSTOM_YOLOLIKE_BOX_OBJECTS, the objects retrieved will be the ones detected using the optimized ObjectDetectionParameters.custom_onnx_file model. When running the detection internally, this method returns the result of the object detection, whether the module is running synchronously or asynchronously. - **Asynchronous:** this method immediately returns the last objects detected. If the current detection isn't done, the objects from the last detection will be returned, and Objects::is_new will be set to false. - **Synchronous:** this method executes detection and waits for it to finish before returning the detected objects. It is recommended to keep the same Objects object as the input of all calls to this method. This will enable the identification and tracking of every object detected. :param py_objects: The detected objects will be saved into this object. If the object already contains data from a previous detection, it will be updated, keeping a unique ID for the same person. :param custom_object_detection_parameters: Custom object detection runtime settings, can be changed at each detection. In async mode, the parameters update is applied on the next iteration. If None, use the previously passed parameters. :param instance_module_id: Id of the object detection instance. Used when multiple instances of the object detection module are enabled at the same time. :return: ERROR_CODE "ERROR_CODE::SUCCESS" if everything went fine, ERROR_CODE "ERROR_CODE::FAILURE" otherwise. set_custom_object_detection_runtime_parameters and retrieve_objects methods should be used instead. objects = sl.Objects() while True: if zed.grab() == sl.ERROR_CODE.SUCCESS: zed.retrieve_custom_objects(objects) object_list = objects.object_list for i in range(len(object_list)): print(repr(object_list[i].label)) ### `get_objects_batch(self, trajectories, instance_module_id=0) -> ERROR_CODE` Get a batch of detected objects. **Warning:** This method needs to be called after retrieve_objects, otherwise trajectories will be empty. It is the retrieve_objects method that ingest the current/live objects into the batching queue. :param trajectories: list of sl.ObjectsBatch that will be filled by the batching queue process. An empty list should be passed to the function :param instance_module_id: Id of the object detection instance. Used when multiple instances of the object detection module are enabled at the same time. :return: ERROR_CODE.SUCCESS if everything went fine :return: ERROR_CODE.INVALID_FUNCTION_CALL if batching module is not available (TensorRT!=7.1) or if object tracking was not enabled. **Note:** Most of the time, the vector will be empty and will be filled every BatchParameters::latency. objects = sl.Objects() # Unique Objects to be updated after each grab while True: # Main loop if zed.grab() == sl.ERROR_CODE.SUCCESS: # Grab an image from the camera zed.retrieve_objects(objects) # Call retrieve_objects so that objects are ingested in the batching system trajectories = [] # Create an empty list of trajectories zed.get_objects_batch(trajectories) # Get batch of objects print("Size of batch: {}".format(len(trajectories))) ### `ingest_custom_box_objects(self, objects_in, instance_module_id=0) -> ERROR_CODE` Feed the 3D Object tracking function with your own 2D bounding boxes from your own detection algorithm. :param objects_in: List of CustomBoxObjectData to feed the object detection. :param instance_module_id: Id of the object detection instance. Used when multiple instances of the object detection module are enabled at the same time. :return: ERROR_CODE.SUCCESS if everything went fine. **Note:** The detection should be done on the current grabbed left image as the internal process will use all currently available data to extract 3D information and perform object tracking. ### `ingest_custom_mask_objects(self, objects_in, instance_module_id=0) -> ERROR_CODE` Feed the 3D Object tracking function with your own 2D bounding boxes with masks from your own detection algorithm. :param objects_in: List of CustomMaskObjectData to feed the object detection. :param instance_module_id: Id of the object detection instance. Used when multiple instances of the object detection module are enabled at the same time. :return: ERROR_CODE.SUCCESS if everything went fine. **Note:** The detection should be done on the current grabbed left image as the internal process will use all currently available data to extract 3D information and perform object tracking. ### `is_object_detection_enabled(self, instance_id=0) -> bool` Tells if the object detection module is enabled. ### `get_sdk_version() -> str` Returns the version of the currently installed ZED SDK. :return: The ZED SDK version as a string with the following format: MAJOR.MINOR.PATCH print(sl.Camera.get_sdk_version()) ### `get_device_list() -> list[DeviceProperties]` List all the connected devices with their associated information. This method lists all the cameras available and provides their serial number, models and other information. :return: The device properties for each connected camera. ### `set_timestamp_clock(clock) -> None` Sets the clock source used for all SDK timestamps (images and sensors). This is a process-wide setting shared by all Camera and CameraOne instances. :param clock: The desired TIMESTAMP_CLOCK. **Note:** Call this before opening any camera. ### `get_timestamp_clock() -> TIMESTAMP_CLOCK` Returns the clock source currently used for SDK timestamps. :return: The active TIMESTAMP_CLOCK. ### `set_max_system_clock_step_ms(limit_ms: float) -> None` Sets the maximum system-clock step (ms) the SDK follows per sample when the host clock is adjusted backward. Only meaningful in SYSTEM_CLOCK mode. See sl.set_max_system_clock_step_ms for the full cheat sheet. ### `get_max_system_clock_step_ms() -> float` Returns the current system-clock step clamp in milliseconds. ### `get_streaming_device_list() -> list[StreamingProperties]` Lists all the streaming devices with their associated information. :return: The streaming properties for each connected camera. **Warning:** This method takes around 2 seconds to make sure all network informations has been captured. Make sure to run this method in a thread. ### `reboot(sn: int, full_reboot: bool=True) -> ERROR_CODE` Performs a hardware reset of the ZED 2 and the ZED 2i. :param sn: Serial number of the camera to reset, or 0 to reset the first camera detected. :param full_reboot: Perform a full reboot (sensors and video modules) if True, otherwise only the video module will be rebooted. :return: ERROR_CODE "ERROR_CODE::SUCCESS" if everything went fine. :return: ERROR_CODE "ERROR_CODE::CAMERA_NOT_DETECTED" if no camera was detected. :return: ERROR_CODE "ERROR_CODE::FAILURE" otherwise. **Note:** This method only works for ZED 2, ZED 2i, and newer camera models. **Warning:** This method will invalidate any sl.Camera object, since the device is rebooting. ### `reboot_from_input(input_type: INPUT_TYPE) -> ERROR_CODE` Performs a hardware reset of all devices matching the InputType. :param input_type: Input type of the devices to reset. :return: ERROR_CODE "ERROR_CODE::SUCCESS" if everything went fine. :return: ERROR_CODE "ERROR_CODE::CAMERA_NOT_DETECTED" if no camera was detected. :return: ERROR_CODE "ERROR_CODE::FAILURE" otherwise. :return: ERROR_CODE "ERROR_CODE::INVALID_FUNCTION_PARAMETERS" for SVOs and streams. **Warning:** This method will invalidate any sl.Camera object, since the device is rebooting. --- # InitParameters Class containing the options used to initialize the sl.Camera object. This class allows you to select multiple parameters for the sl.Camera such as the selected camera, resolution, depth mode, coordinate system, and units of measurement. Once filled with the desired options, it should be passed to the sl.Camera.open() method. import pyzed.sl as sl def main() : zed = sl.Camera() # Create a ZED camera object init_params = sl.InitParameters() # Set initial parameters init_params.sdk_verbose = 0 # Disable verbose mode # Use the camera in LIVE mode init_params.camera_resolution = sl.RESOLUTION.HD1080 # Use HD1080 video mode init_params.camera_fps = 30 # Set fps at 30 # Or use the camera in SVO (offline) mode #init_params.set_from_svo_file("xxxx.svo") # Or use the camera in STREAM mode #init_params.set_from_stream("192.168.1.12", 30000) # Other parameters are left to their default values # Open the camera err = zed.open(init_params) if err != sl.ERROR_CODE.SUCCESS: exit(-1) # Close the camera zed.close() return 0 if __name__ == "__main__" : main() With its default values, it opens the camera in live mode at sl.RESOLUTION.AUTO (which resolves to sl.RESOLUTION.HD1200 for the ZED X/X Mini, sl.RESOLUTION.HD720 for other cameras) and sets the depth mode to sl.DEPTH_MODE.NEURAL You can customize it to fit your application. **Note:** The parameters can also be saved and reloaded using its save() and load() methods. ## Properties ### `sdk_verbose: int` *(read/write)* Enable the ZED SDK verbose mode. This parameter allows you to enable the verbosity of the ZED SDK to get a variety of runtime information in the console. When developing an application, enabling verbose (``sdk_verbose >= 1``) mode can help you understand the current ZED SDK behavior. However, this might not be desirable in a shipped version. Default: 1 (verbose messages enabled) **Note:** The verbose messages can also be exported into a log file. **Note:** See sdk_verbose_log_file for more. ### `depth_mode: DEPTH_MODE` *(read/write)* sl.DEPTH_MODE to be used. The ZED SDK offers several sl.DEPTH_MODE, offering various levels of performance and accuracy. This parameter allows you to set the sl.DEPTH_MODE that best matches your needs. Default: sl.DEPTH_MODE.NEURAL **Note:** Available depth mode are listed here: sl.DEPTH_MODE. ### `camera_image_flip: FLIP_MODE` *(read/write)* Defines if a flip of the images is needed. If you are using the camera upside down, setting this parameter to sl.FLIP_MODE.ON will cancel its rotation. The images will be horizontally flipped. Default: sl.FLIP_MODE.AUTO **Note:** From ZED SDK 3.2 a new sl.FLIP_MODE enum was introduced to add the automatic flip mode detection based on the IMU gravity detection. **Note:** This does not work on sl.MODEL.ZED cameras since they do not have the necessary sensors. ### `enable_right_side_measure: bool` *(read/write)* Enable the measurement computation on the right images. By default, the ZED SDK only computes a single depth map, aligned with the left camera image. This parameter allows you to enable sl.MEASURE.DEPTH_RIGHT and other sl.MEASURE.XXX_RIGHT at the cost of additional computation time. For example, mixed reality pass-through applications require one depth map per eye, so this parameter can be activated. Default: False ### `svo_real_time_mode: bool` *(read/write)* Defines if sl.Camera object return the frame in real time mode. When playing back an SVO file, each call to sl.Camera.grab() will extract a new frame and use it. However, it ignores the real capture rate of the images saved in the SVO file. Enabling this parameter will bring the SDK closer to a real simulation when playing back a file by using the images' timestamps. Default: False **Note:** sl.Camera.grab() will return an error when trying to play too fast, and frames will be dropped when playing too slowly. ### `depth_maximum_distance: float` *(read/write)* Maximum depth distance to be returned, measured in the sl.UNIT defined in coordinate_units. When estimating the depth, the ZED SDK uses this upper limit to turn higher values into **inf** ones. Changing this value has no impact on performance and doesn't affect the positional tracking nor the spatial mapping. It only change values the depth, point cloud and normals. Setting this value to any negative or null value will select the default maximum depth distance available. Default: -1 ### `async_grab_camera_recovery: bool` *(read/write)* Define the behavior of the automatic camera recovery during sl.Camera.grab() method call. When async is enabled and there's an issue with the communication with the sl.Camera object, sl.Camera.grab() will exit after a short period and return the sl.ERROR_CODE.CAMERA_REBOOTING warning. The recovery will run in the background until the correct communication is restored. When async_grab_camera_recovery is false, the sl.Camera.grab() method is blocking and will return only once the camera communication is restored or the timeout is reached. Default: False ### `camera_resolution: RESOLUTION` *(read/write)* Desired camera resolution. **Note:** Small resolutions offer higher framerate and lower computation time. **Note:** In most situations, sl.RESOLUTION.HD720 at 60 FPS is the best balance between image quality and framerate. Default: sl.RESOLUTION.AUTO * Resolves to sl.RESOLUTION.HD1200 for ZED X/X Mini * Resolves to sl.RESOLUTION.HD720 for other cameras **Note:** Available resolutions are listed here: sl.RESOLUTION. ### `sensors_required: bool` *(read/write)* Requires the successful opening of the motion sensors before opening the camera. Default: False. **Note:** If set to false, the ZED SDK will try to **open and use** the IMU (second USB device on USB2.0) and will open the camera successfully even if the sensors failed to open. This can be used for example when using a USB3.0 only extension cable (some fiber extension for example). **Note:** This parameter only impacts the LIVE mode. **Note:** If set to true, sl.Camera.open() will fail if the sensors cannot be opened. **Note:** This parameter should be used when the IMU data must be available, such as object detection module or when the gravity is needed. Note: This setting is not taken into account for sl.MODEL.ZED camera since it does not include sensors. ### `coordinate_system: COORDINATE_SYSTEM` *(read/write)* sl.COORDINATE_SYSTEM to be used as reference for positional tracking, mesh, point clouds, etc. This parameter allows you to select the sl.COORDINATE_SYSTEM used by the sl.Camera object to return its measures. This defines the order and the direction of the axis of the coordinate system. Default: sl.COORDINATE_SYSTEM.IMAGE ### `enable_image_validity_check: int` *(read/write)* Enable or disable the image validity verification. This will perform additional verification on the image to identify corrupted data. This verification is done in the sl.Camera.grab() method and requires some computations. If an issue is found, the sl.Camera.grab() method will output a warning as sl.ERROR_CODE.CORRUPTED_FRAME. This version doesn't detect frame tearing currently. Default: True (enabled) ### `async_image_retrieval: bool` *(read/write)* Enable async image retrieval. \deprecated This parameter is deprecated and no longer has any effect. If set to true will camera image retrieve at a framerate different from grab() application framerate. This is useful for recording SVO or sending camera stream at different rate than application. Default: false ### `optional_opencv_calibration_file: str` *(read/write)* Optional path where the ZED SDK can find a file containing the calibration information of the camera computed by OpenCV. **Note:** Using this will disable the factory calibration of the camera. **Note:** The file must be in a XML/YAML/JSON formatting provided by OpenCV. **Note:** It also must contain the following keys: Size, K_LEFT (intrinsic left), K_RIGHT (intrinsic right), D_LEFT (distortion left), D_RIGHT (distortion right), R (extrinsic rotation), T (extrinsic translation). **Warning:** Erroneous calibration values can lead to poor accuracy in all ZED SDK modules. ### `camera_fps: int` *(read/write)* Requested camera frame rate. If set to 0, the highest FPS of the specified camera_resolution will be used. Default: 0 See sl.RESOLUTION for a list of supported frame rates. **Note:** If the requested camera_fps is unsupported, the closest available FPS will be used. ### `sdk_gpu_id: int` *(read/write)* NVIDIA graphics card id to use. By default the SDK will use the most powerful NVIDIA graphics card found. However, when running several applications, or using several cameras at the same time, splitting the load over available GPUs can be useful. This parameter allows you to select the GPU used by the sl.Camera using an ID from 0 to n-1 GPUs in your PC. Default: -1 **Note:** A non-positive value will search for all CUDA capable devices and select the most powerful. ### `svo_decryption_key: str` *(read/write)* Optional passphrase or key to decrypt an encrypted SVO file. Required when opening an SVO file that was recorded with RecordingParameters.encryption_key. The value is interpreted as a file path (raw 32-byte or hex key file), a 64-char hex string (raw AES-256 key), or a passphrase (PBKDF2-SHA256 derived). Default: "" (no decryption) **Note:** If the SVO file is encrypted and this field is empty or contains a wrong key, sl.Camera.open() will return sl.ERROR_CODE.INVALID_SVO_FILE. ### `enable_image_enhancement: bool` *(read/write)* Enable the Enhanced Contrast Technology, to improve image quality. Default: True. If set to true, image enhancement will be activated in camera ISP. Otherwise, the image will not be enhanced by the IPS. **Note:** This only works for firmware version starting from 1523 and up. ### `camera_disable_self_calib: bool` *(read/write)* Disables the self-calibration process at camera opening. At initialization, sl.Camera runs a self-calibration process that corrects small offsets from the device's factory calibration. A drawback is that calibration parameters will slightly change from one (live) run to another, which can be an issue for repeatability. If set to true, self-calibration will be disabled and calibration parameters won't be optimized, raw calibration parameters from the configuration file will be used. Default: false **Note:** In most situations, self calibration should remain enabled. **Note:** You can also trigger the self-calibration at anytime after sl.Camera.open() by calling sl.Camera.update_self_calibration(), even if this parameter is set to true. ### `sdk_verbose_log_file: str` *(read/write)* File path to store the ZED SDK logs (if sdk_verbose is enabled). The file will be created if it does not exist. Default: "" **Note:** Setting this parameter to any value will redirect all standard output print calls of the entire program. **Note:** This means that your own standard output print calls will be redirected to the log file. **Warning:** The log file won't be cleared after successive executions of the application. **Warning:** This means that it can grow indefinitely if not cleared. ### `maximum_working_resolution: Resolution` *(read/write)* Set a maximum size for all SDK output, like retrieveImage and retrieveMeasure functions. This will override the default (0,0) and instead of outputting native image size sl::Mat, the ZED SDK will take this size as default. A custom lower size can also be used at runtime, but not bigger. This is used for internal optimization of compute and memory allocations The default is similar to previous version with (0,0), meaning native image size **Note:** : if maximum_working_resolution field are lower than 64, it will be interpreted as dividing scale factor; - maximum_working_resolution = sl::Resolution(1280, 16) -> 1280 x (image_height/2) = 1280 x half height - maximum_working_resolution = sl::Resolution(4, 4) -> (image_width/4) x (image_height/4) = quarter size ### `optional_settings_path: str` *(read/write)* Optional path where the ZED SDK has to search for the settings file (SN.conf file). This file contains the calibration information of the camera. Default: "" **Note:** The settings file will be searched in the default directory: * **Linux**: /usr/local/zed/settings/ * **Windows**: C:/ProgramData/stereolabs/settings **Note:** If a path is specified and no file has been found, the ZED SDK will search the settings file in the default directory. **Note:** An automatic download of the settings file (through **ZED Explorer** or the installer) will still download the files on the default path. init_params = sl.InitParameters() # Set initial parameters home = "/path/to/home" path = home + "/Documents/settings/" # assuming /path/to/home/Documents/settings/SNXXXX.conf exists. Otherwise, it will be searched in /usr/local/zed/settings/ init_params.optional_settings_path = path ### `input: InputType` *(read/write)* The SDK can handle different input types: - Select a camera by its ID (/dev/videoX on Linux, and 0 to N cameras connected on Windows) - Select a camera by its serial number - Open a recorded sequence in the SVO file format - Open a streaming camera from its IP address and port This parameter allows you to select to desired input. It should be used like this: init_params = sl.InitParameters() # Set initial parameters init_params.sdk_verbose = 1 # Enable verbose mode input_t = sl.InputType() input_t.set_from_camera_id(0) # Selects the camera with ID = 0 init_params.input = input_t init_params.set_from_camera_id(0) # You can also use this init_params = sl.InitParameters() # Set initial parameters init_params.sdk_verbose = 1 # Enable verbose mode input_t = sl.InputType() input_t.set_from_serial_number(1010) # Selects the camera with serial number = 101 init_params.input = input_t init_params.set_from_serial_number(1010) # You can also use this init_params = sl.InitParameters() # Set initial parameters init_params.sdk_verbose = 1 # Enable verbose mode input_t = sl.InputType() input_t.set_from_svo_file("/path/to/file.svo") # Selects the and SVO file to be read init_params.input = input_t init_params.set_from_svo_file("/path/to/file.svo") # You can also use this init_params = sl.InitParameters() # Set initial parameters init_params.sdk_verbose = 1 # Enable verbose mode input_t = sl.InputType() input_t.set_from_stream("192.168.1.42") init_params.input = input_t init_params.set_from_stream("192.168.1.42") # You can also use this Available cameras and their ID/serial can be listed using get_device_list() and get_streaming_device_list() Each Camera will create its own memory (CPU and GPU), therefore the number of ZED used at the same time can be limited by the configuration of your computer. (GPU/CPU memory and capabilities) default : empty See InputType for complementary information. **Warning:** Using the ZED SDK Python API, using init_params.input.set_from_XXX won't work, use init_params.set_from_XXX instead ### `grab_compute_capping_fps: float` *(read/write)* Define a computation upper limit to the grab frequency. This can be useful to get a known constant fixed rate or limit the computation load while keeping a short exposure time by setting a high camera capture framerate. The value should be inferior to the sl.InitParameters.camera_fps and strictly positive. **Note:** It has no effect when reading an SVO file. This is an upper limit and won't make a difference if the computation is slower than the desired compute capping FPS. **Note:** Internally the sl.Camera.grab() method always tries to get the latest available image while respecting the desired FPS as much as possible. ### `open_timeout_sec: float` *(read/write)* Define a timeout in seconds after which an error is reported if the sl.Camera.open() method fails. Set to '-1' to try to open the camera endlessly without returning error in case of failure. Set to '0' to return error in case of failure at the first attempt. Default: 5.0 **Note:** This parameter only impacts the LIVE mode. ### `depth_stabilization: int` *(read/write)* Defines whether the depth needs to be stabilized and to what extent. Regions of generated depth map can oscillate from one frame to another. These oscillations result from a lack of texture (too homogeneous) on an object and by image noise. This parameter controls a stabilization filter that reduces these oscillations. In the range [0-100]: * 0 disable the depth stabilization (raw depth will be return) * stabilization smoothness is linear from 1 to 100 Default: 30 **Note:** The stabilization uses the positional tracking to increase its accuracy, so the positional tracking module will be enabled automatically when set to a value different from 0. **Note:** Note that calling sl.Camera.enable_positional_tracking() with your own parameters afterwards is still possible. ### `depth_minimum_distance: float` *(read/write)* Minimum depth distance to be returned, measured in the sl.UNIT defined in coordinate_units. This parameter allows you to specify the minimum depth value (from the camera) that will be computed. Setting this value to any negative or null value will select the default minimum depth distance available for the used ZED Camera (depending on the camera focal length and baseline). Default: -1 When using deprecated depth modes ( sl.DEPTH_MODE.PERFORMANCE, sl.DEPTH_MODE.QUALITY or sl.DEPTH_MODE.ULTRA), the default minimum depth distances are given by `this table `_. **Note:** This value cannot be greater than 3 meters. ### `coordinate_units: UNIT` *(read/write)* Unit of spatial data (depth, point cloud, tracking, mesh, etc.) for retrieval. Default: sl.UNIT.MILLIMETER ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `save(self, filename) -> bool` Saves the current set of parameters into a file to be reloaded with the load() method. :param filename: Name of the file which will be created to store the parameters (extension '.yml' will be added if not set). :return: True if file was successfully saved, otherwise False. **Warning:** For security reason, the file must not exist. **Warning:** In case a file already exists, the method will return False and existing file will not be updated init_params = sl.InitParameters() # Set initial parameters init_params.sdk_verbose = 1 # Enable verbose mode init_params.set_from_svo_file("/path/to/file.svo") # Selects the and SVO file to be read init_params.save("initParameters.conf") # Export the parameters into a file ### `load(self, filename) -> bool` Loads a set of parameters from the values contained in a previously save() "saved" file. :param filename: Path to the file from which the parameters will be loaded (extension '.yml' will be added at the end of the filename if not set). :return: True if the file was successfully loaded, otherwise false. init_params = sl.InitParameters() # Set initial parameters init_params.load("initParameters.conf") # Load the init_params from a previously exported file ### `set_from_camera_id(self, cam_id, bus_type: BUS_TYPE=BUS_TYPE.AUTO) -> None` Defines the input source with a camera id to initialize and open an sl.Camera object from. :param id: Id of the desired camera to open. :param bus_type: sl.BUS_TYPE of the desired camera to open. ### `set_from_serial_number(self, serial_number) -> None` Defines the input source with a serial number to initialize and open an sl.Camera object from. For ZED/ZEDOne cameras (numeric serial numbers), pass an int or a numeric string. For Lidar sensors (string-based serial numbers like "991937000508"), pass a string. :param serial_number: Serial number of the desired camera/sensor to open (int or str). ### `set_from_svo_file(self, svo_input_filename) -> None` Defines the input source with an SVO file to initialize and open an sl.Camera object from. :param svo_input_filename: Path to the desired SVO file to open. ### `set_from_stream(self, sender_ip, port=30000) -> None` Defines the input source from a stream to initialize and open an sl.Camera object from. :param sender_ip: IP address of the streaming sender. :param port: Port on which to listen. Default: 30000 ### `set_from_gmsl_port(self, gmsl_port=-1) -> None` Defines the input source as the camera with the specified GMSL port. :param gmsl_port: GMSL port number of the camera to open. Default: -1. Any number < 0 will try to open the first available GMSL camera. ### `set_virtual_stereo_from_camera_id(self, id_left, id_right, virtual_serial_number) -> bool` Defines the input as a virtual stereo camera built from two cameras with the specified ids. :param id_left: Id of the left camera. :param id_right: Id of the right camera. :param virtual_serial_number: Serial number of the virtual stereo camera. **Note:** : The virtual serial number must fall within an interval that reflects the Product ID range. This is necessary to avoid, for instance, downloading calibration data from an unrelated product. The valid range is 110000000 to 119999999. A support function can be used, based on the ZED One serial number, to compute a valid virtual serial number: generate_virtual_stereo_serial_number :return: False if there's no error and the camera was successfully created, otherwise True. ### `set_virtual_stereo_from_serial_numbers(self, camera_left_serial_number, camera_right_serial_number, virtual_serial_number) -> bool` Defines the input as a virtual stereo camera built from two cameras with the specified serial numbers. :param camera_left_serial_number: Serial number of the left camera. :param camera_right_serial_number: Serial number of the right camera. :param virtual_serial_number: Serial number of the virtual stereo camera. **Note:** : The virtual serial number must fall within an interval that reflects the Product ID range. This is necessary to avoid, for instance, downloading calibration data from an unrelated product. The valid range is 110000000 to 119999999. A support function can be used, based on the ZED One serial number, to compute a valid virtual serial number: generate_virtual_stereo_serial_number :return: False if there's no error and the camera was successfully created, otherwise True. --- # RuntimeParameters Class containing parameters that defines the behavior of sl.Camera.grab(). The default constructor sets all parameters to their default settings. **Note:** Parameters can be adjusted by the user. ## Properties ### `remove_saturated_areas: bool` *(read/write)* Defines if the saturated area (luminance>=255) must be removed from depth map estimation. Default: True **Note:** It is recommended to keep this parameter at True because saturated area can create false detection. ### `measure3D_reference_frame: REFERENCE_FRAME` *(read/write)* Reference frame in which to provides the 3D measures (point cloud, normals, etc.). Default: sl.REFERENCE_FRAME.CAMERA ### `enable_fill_mode: bool` *(read/write)* Defines if the depth map should be completed or not. Default: False **Note:** It is similar to the removed sl.SENSING_MODE.FILL. **Warning:** Enabling this will override the confidence values confidence_threshold and texture_confidence_threshold as well as remove_saturated_areas. ### `texture_confidence_threshold: int` *(read/write)* Threshold to reject depth values based on their texture confidence. The texture confidence range is [1, 100]. Decreasing this value will remove depth data from image areas which are uniform. Default: 100 (no depth pixel will be rejected) **Note:** Pixels with a value close to 100 are not to be trusted. Accurate depth pixels tends to be closer to lower values. ### `confidence_threshold: int` *(read/write)* Threshold to reject depth values based on their confidence. Each depth pixel has a corresponding confidence (sl.MEASURE.CONFIDENCE) in the range [1, 100]. Decreasing this value will remove depth data from both objects edges and low textured areas, to keep only confident depth estimation data. Default: 95 (no depth pixel will be rejected) **Note:** Pixels with a value close to 100 are not to be trusted. Accurate depth pixels tends to be closer to lower values. **Note:** It can be seen as a probability of error, scaled to 100. ### `enable_depth: bool` *(read/write)* Defines if the depth map should be computed. Default: True **Note:** If set to False, only the images are available. ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `save(self, filename: str) -> bool` Saves the current set of parameters into a file to be reloaded with the load() method. :param filename: Name of the file which will be created to store the parameters (extension '.yml' will be added if not set). :return: True if the file was successfully saved, otherwise False. **Warning:** For security reasons, the file must not already exist. **Warning:** In case a file already exists, the method will return False and existing file will not be updated. ### `load(self, filename: str) -> bool` Loads a set of parameters from the values contained in a previously save() "saved" file. :param filename: Path to the file from which the parameters will be loaded (extension '.yml' will be added at the end of the filename if not detected). :return: True if the file was successfully loaded, otherwise False. --- # Mat Class representing 1 to 4-channel matrix of float or uchar, stored on CPU and/or GPU side. This class is defined in a row-major order, meaning that for an image buffer, the rows are stored consecutively from top to bottom. **Note:** The ZED SDK Python wrapper does not support GPU data storage/access. ## Properties ### `timestamp: Timestamp` *(read/write)* Timestamp of the last manipulation of the data of the matrix by a method/function. ### `verbose: bool` *(read/write)* Whether the sl.Mat can display information. ### `name: str` *(read/write)* The name of the sl.Mat (optional). In verbose mode, it iss used to indicate which sl.Mat is printing information. Default set to "n/a" to avoid empty string if not filled. ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `init_mat_type(self, width, height, mat_type, memory_type=MEM.CPU) -> None` Initilizes a new sl.Mat and allocates the requested memory by calling alloc_size(). :param width: Width of the matrix in pixels. Default: 0 :param height: Height of the matrix in pixels. Default: 0 :param mat_type: Type of the matrix (sl.MAT_TYPE.F32_C1, sl.MAT_TYPE.U8_C4, etc.). Default: sl.MAT_TYPE.F32_C1 :param memory_type: Where the buffer will be stored. Default: sl.MEM.CPU (you cannot change this default value) ### `init_mat_cpu(self, width: int, height: int, mat_type: MAT_TYPE, ptr, step, memory_type=MEM.CPU) -> None` Initilizes a new sl.Mat from an existing data pointer. This method does not allocate the memory. :param width: Width of the matrix in pixels. :param height: Height of the matrix in pixels. :param mat_type: Type of the matrix (sl.MAT_TYPE.F32_C1, sl.MAT_TYPE.U8_C4, etc.). Default: sl.MAT_TYPE.F32_C1 :param ptr: Memory address of the data array as an integer (e.g. ``my_numpy_array.ctypes.data``). :param step: Step of the data array (bytes size of one pixel row). :param memory_type: Where the buffer will be stored. Default: sl.MEM.CPU (you cannot change this default value) arr = np.zeros((height, width, 4), dtype=np.uint8) mat = sl.Mat() mat.init_mat_cpu(width, height, sl.MAT_TYPE.U8_C4, arr.ctypes.data, arr.strides[0]) ### `init_mat_resolution(self, resolution: Resolution, mat_type: MAT_TYPE, memory_type=MEM.CPU) -> None` Initilizes a new sl.Mat and allocates the requested memory by calling alloc_size(). :param resolution: Size of the matrix in pixels. :param mat_type: Type of the matrix (sl.MAT_TYPE.F32_C1, sl.MAT_TYPE.U8_C4, etc.). Default: sl.MAT_TYPE.F32_C1 :param memory_type: Where the buffer will be stored. Default: sl.MEM.CPU (you cannot change this default value) ### `init_mat_resolution_cpu(self, resolution: Resolution, mat_type, ptr, step, memory_type=MEM.CPU) -> None` Initilizes a new sl.Mat from an existing data pointer. This method does not allocate the memory. :param resolution: the size of the matrix in pixels. :param mat_type: Type of the matrix (sl.MAT_TYPE.F32_C1, sl.MAT_TYPE.U8_C4, etc.). Default: sl.MAT_TYPE.F32_C1 :param ptr: Memory address of the data array as an integer (e.g. ``my_numpy_array.ctypes.data``). :param step: Step of the data array (bytes size of one pixel row). :param memory_type: Where the buffer will be stored. Default: sl.MEM.CPU (you cannot change this default value) ### `init_mat(self, matrix: Mat) -> None` Initilizes a new sl.Mat by copy (shallow copy). This method does not allocate the memory. :param mat: sl.Mat to copy. ### `alloc_size(self, width, height, mat_type, memory_type=MEM.CPU) -> None` Allocates the sl.Mat memory. :param width: Width of the matrix in pixels. :param height: Height of the matrix in pixels. :param mat_type: Type of the matrix (sl.MAT_TYPE.F32_C1, sl.MAT_TYPE.U8_C4, etc.). Default: sl.MAT_TYPE.F32_C1 :param memory_type: Where the buffer will be stored. Default: sl.MEM.CPU (you cannot change this default value) **Warning:** It erases previously allocated memory. ### `alloc_resolution(self, resolution: Resolution, mat_type: MAT_TYPE, memory_type=MEM.CPU) -> None` Allocates the sl.Mat memory. :param resolution: Size of the matrix in pixels. :param mat_type: Type of the matrix (sl.MAT_TYPE.F32_C1, sl.MAT_TYPE.U8_C4, etc.). Default: sl.MAT_TYPE.F32_C1 :param memory_type: Where the buffer will be stored. Default: sl.MEM.CPU (you cannot change this default value) **Warning:** It erases previously allocated memory. ### `free(self, memory_type=MEM.CPU) -> None` Free the owned memory. :param memory_type: Specifies which memory you wish to free. Default: sl.MEM.CPU (you cannot change this default value) ### `copy_to(self, dst: Mat, cpy_type=COPY_TYPE.CPU_CPU) -> ERROR_CODE` Copies data to another sl.Mat (deep copy). :param dst: sl.Mat where the data will be copied to. :param cpy_type: Specifies the memory that will be used for the copy. Default: sl.COPY_TYPE.CPU_CPU (you cannot change this default value) :return: sl.ERROR_CODE.SUCCESS if everything went well, sl.ERROR_CODE.FAILURE otherwise. **Note:** If the destination is not allocated or does not have a compatible sl.MAT_TYPE or sl.Resolution, current memory is freed and new memory is directly allocated. ### `update_cpu_from_gpu(self) -> ERROR_CODE` Downloads data from DEVICE (GPU) to HOST (CPU), if possible. **Note:** If no CPU or GPU memory are available for this sl::Mat, some are directly allocated. **Note:** If verbose is set to true, you have information in case of failure. ### `update_gpu_from_cpu(self) -> ERROR_CODE` Uploads data from HOST (CPU) to DEVICE (GPU), if possible. **Note:** If no CPU or GPU memory are available for this sl::Mat, some are directly allocated. **Note:** If verbose is set to true, you have information in case of failure. ### `set_from(self, src: Mat, cpy_type=COPY_TYPE.CPU_CPU) -> ERROR_CODE` Copies data from an other sl.Mat (deep copy). :param src: sl.Mat where the data will be copied from. :param cpy_type: Specifies the memory that will be used for the copy. Default: sl.COPY_TYPE.CPU_CPU (you cannot change this default value) :return: sl.ERROR_CODE.SUCCESS if everything went well, sl.ERROR_CODE.FAILURE otherwise. **Note:** If the destination is not allocated or does not have a compatible sl.MAT_TYPE or sl.Resolution, current memory is freed and new memory is directly allocated. ### `read(self, filepath: str) -> ERROR_CODE` Reads an image from a file (only if sl.MEM.CPU is available on the current sl.Mat). Supported input files format are PNG and JPEG. :param filepath: Path of the file to read from (including the name and extension). :return: sl.ERROR_CODE.SUCCESS if everything went well, sl.ERROR_CODE.FAILURE otherwise. **Note:** Supported sl.MAT_TYPE are : - MAT_TYPE.F32_C1 for PNG/PFM/PGM - MAT_TYPE.F32_C3 for PCD/PLY/VTK/XYZ - MAT_TYPE.F32_C4 for PCD/PLY/VTK/WYZ - MAT_TYPE.U8_C1 for PNG/JPG - MAT_TYPE.U8_C3 for PNG/JPG - MAT_TYPE.U8_C4 for PNG/JPG ### `write(self, filepath: str, memory_type=MEM.CPU, compression_level=-1) -> ERROR_CODE` Writes the sl.Mat (only if sl.MEM.CPU is available on the current sl.Mat) into a file as an image. Supported output files format are PNG and JPEG. :param filepath: Path of the file to write (including the name and extension). :param memory_type: Memory type of the sl.Mat. Default: sl.MEM.CPU (you cannot change the default value) :param compression_level: Level of compression between 0 (lowest compression == highest size == highest quality(jpg)) and 100 (highest compression == lowest size == lowest quality(jpg)). **Note:** Specific/default value for compression_level = -1 : This will set the default quality for PNG(30) or JPEG(5). **Note:** compression_level is only supported for [U8_Cx] (MAT_TYPE). :return: sl.ERROR_CODE.SUCCESS if everything went well, sl.ERROR_CODE.FAILURE otherwise. **Note:** Supported sl.MAT_TYPE are : - MAT_TYPE.F32_C1 for PNG/PFM/PGM - MAT_TYPE.F32_C3 for PCD/PLY/VTK/XYZ - MAT_TYPE.F32_C4 for PCD/PLY/VTK/WYZ - MAT_TYPE.U8_C1 for PNG/JPG - MAT_TYPE.U8_C3 for PNG/JPG - MAT_TYPE.U8_C4 for PNG/JPG ### `set_to(self, value, memory_type=MEM.CPU) -> ERROR_CODE` Fills the sl.Mat with the given value. This method overwrites all the matrix. :param value: Value to be copied all over the matrix. :param memory_type: Which buffer to fill. Default: sl.MEM.CPU (you cannot change the default value) ### `set_value(self, x: int, y: int, value, memory_type=MEM.CPU) -> ERROR_CODE` Sets a value to a specific point in the matrix. :param x: Column of the point to change. :param y: Row of the point to change. :param value: Value to be set. :param memory_type: Which memory will be updated. :return: sl.ERROR_CODE.SUCCESS if everything went well, sl.ERROR_CODE.FAILURE otherwise. **Warning:** Not efficient for sl.MEM.GPU, use it on sparse data. ### `get_value(self, x: int, y: int, memory_type=MEM.CPU) -> Tuple[ERROR_CODE, np.ndarray[Any]]` Returns the value of a specific point in the matrix. :param x: Column of the point to get the value from. :param y: Row of the point to get the value from. :param memory_type: Which memory should be read. :return: sl.ERROR_CODE.SUCCESS if everything went well, sl.ERROR_CODE.FAILURE otherwise. **Warning:** Not efficient for sl.MEM.GPU, use it on sparse data. ### `get_width(self) -> int` Returns the width of the matrix. :return: Width of the matrix in pixels. ### `get_height(self) -> int` Returns the height of the matrix. :return: Height of the matrix in pixels. ### `get_resolution(self) -> Resolution` Returns the resolution (width and height) of the matrix. :return: Resolution of the matrix in pixels. ### `get_channels(self) -> int` Returns the number of values stored in one pixel. :return: Number of values in a pixel. ### `get_data_type(self) -> MAT_TYPE` Returns the format of the matrix. :return: Format of the current sl.Mat. ### `get_memory_type(self) -> MEM` Returns the type of memory (CPU and/or GPU). :return: Type of allocated memory. ### `numpy(self, force=False) -> npt.NDArray` Returns the sl.Mat as a NumPy array. This is for convenience to mimic the [PyTorch API](https://pytorch.org/docs/stable/generated/torch.Tensor.numpy.html). This is like an alias of get_data() method. :param force: Whether the memory of the sl.Mat need to be duplicated. :return: NumPy array containing the sl.Mat data. **Note:** The fastest is **force at False but the sl.Mat memory must not be released to use the NumPy array. ### `get_data(self, memory_type=MEM.CPU, deep_copy=False) -> npt.NDArray` Cast the data of the sl.Mat in a NumPy array (with or without copy). :param memory_type: Which memory should be read. If MEM.GPU, you should have CuPy installed. Default: MEM.CPU :param deep_copy: Whether the memory of the sl.Mat need to be duplicated. :return: NumPy array containing the sl.Mat data. **Note:** The fastest is **deep_copy at False but the sl.Mat memory must not be released to use the NumPy array. ### `get_step_bytes(self, memory_type=MEM.CPU) -> int` Returns the memory step in bytes (size of one pixel row). :param memory_type: Specifies whether you want sl.MEM.CPU or sl.MEM.GPU step. Default: sl.MEM.CPU (you cannot change the default value) :return: The step in bytes of the specified memory. ### `get_step(self, memory_type=MEM.CPU) -> int` Returns the memory step in number of elements (size in one pixel row). :param memory_type: Specifies whether you want sl.MEM.CPU or sl.MEM.GPU step. Default: sl.MEM.CPU (you cannot change the default value) :return: The step in number of elements. ### `get_pixel_bytes(self) -> int` Returns the size of one pixel in bytes. :return: Size of a pixel in bytes. ### `get_width_bytes(self) -> int` Returns the size of a row in bytes. :return: Size of a row in bytes. ### `get_infos(self) -> str` Returns the information about the sl.Mat into a string. :return: String containing the sl.Mat information. ### `is_init(self) -> bool` Returns whether the sl.Mat is initialized or not. :return: True if current sl.Mat has been allocated (by the constructor or therefore). ### `is_memory_owner(self) -> bool` Returns whether the sl.Mat is the owner of the memory it accesses. If not, the memory won't be freed if the sl.Mat is destroyed. :return: True if the sl.Mat is owning its memory, else False. ### `clone(self, py_mat) -> ERROR_CODE` Duplicates a sl.Mat by copy (deep copy). :param py_mat: sl.Mat to copy. This method copies the data array(s) and it marks the new sl.Mat as the memory owner. ### `move(self, py_mat) -> ERROR_CODE` Moves the data of the sl.Mat to another sl.Mat. This method gives the attribute of the current s.Mat to the specified one. (No copy.) :param py_mat: sl.Mat to move to. **Note:** : The current sl.Mat is then no more usable since its loose its attributes. ### `convert_color_inplace(self, memory_type=MEM.CPU) -> ERROR_CODE` Convert the color channels of the Mat (RGB<->BGR or RGBA<->BGRA) This methods works only on 8U_C4 or 8U_C3 ### `convert_color(mat1, mat2, swap_RB_channels, remove_alpha_channels, memory_type=MEM.CPU) -> ERROR_CODE` Convert the color channels of the Mat into another Mat This methods works only on 8U_C4 if remove_alpha_channels is enabled, or 8U_C4 and 8U_C3 if swap_RB_channels is enabled The inplace method sl::Mat::convertColor can be used for only swapping the Red and Blue channel efficiently ### `swap(mat1, mat2) -> None` Swaps the content of the provided sl::Mat (only swaps the pointers, no data copy). :param mat1: First matrix to swap. :param mat2: Second matrix to swap. ### `get_pointer(self, memory_type=MEM.CPU) -> int` Gets the pointer of the content of the sl.Mat. :param memory_type: Which memory you want to get. Default: sl.MEM.CPU (you cannot change the default value) :return: Pointer of the content of the sl.Mat. --- # ERROR_CODE *(enum)* Lists error codes in the ZED SDK. | Enumerator | | |:---:|:---:| | SENSOR_CONFIGURATION_CHANGED | The sensor's configuration was changed externally while streaming. If auto_recovery_on_config_change is enabled, the SDK will automatically reconnect. | | POTENTIAL_CALIBRATION_ISSUE | The camera has a potential calibration issue. | | CONFIGURATION_FALLBACK | The operation could not proceed with the target configuration but did success with a fallback. | | SENSORS_DATA_REQUIRED | The input data does not contains the high frequency sensors data, this is usually because it requires newer SVO/Streaming. In order to work this modules needs inertial data present in it input. | | CORRUPTED_FRAME | The image is corrupted with invalid colors (green/purple images). This indicates a serious hardware or driver issue. | CAMERA_REBOOTING | The camera is currently rebooting. | | SUCCESS | Standard code for successful behavior. | | FAILURE | Standard code for unsuccessful behavior. | | NO_GPU_COMPATIBLE | No GPU found or CUDA capability of the device is not supported. | | NOT_ENOUGH_GPU_MEMORY | Not enough GPU memory for this depth mode. Try a different mode (such as PERFORMANCE), or increase the minimum depth value (see InitParameters.depth_minimum_distance). | | CAMERA_NOT_DETECTED | No camera was detected. | | SENSORS_NOT_INITIALIZED | The MCU that controls the sensors module has an invalid serial number. You can try to recover it by launching the **ZED Diagnostic** tool from the command line with the option ``-r``. | | SENSORS_NOT_AVAILABLE | A camera with sensor is detected but the sensors (IMU, barometer, ...) cannot be opened. Only the MODEL.ZED does not has sensors. Unplug/replug is required. | | INVALID_RESOLUTION | In case of invalid resolution parameter, such as an upsize beyond the original image size in Camera.retrieve_image. | | LOW_USB_BANDWIDTH | Insufficient bandwidth for the correct use of the camera. This issue can occur when you use multiple cameras or a USB 2.0 port. | | CALIBRATION_FILE_NOT_AVAILABLE | The calibration file of the camera is not found on the host machine. Use **ZED Explorer** or **ZED Calibration** to download the factory calibration file. | | INVALID_CALIBRATION_FILE | The calibration file is not valid. Try to download the factory calibration file or recalibrate your camera using **ZED Calibration**. | | INVALID_SVO_FILE | The provided SVO file is not valid. | | SVO_RECORDING_ERROR | An error occurred while trying to record an SVO (not enough free storage, invalid file, ...). | | SVO_UNSUPPORTED_COMPRESSION | An SVO related error, occurs when NVIDIA based compression cannot be loaded. | | END_OF_SVOFILE_REACHED | SVO end of file has been reached. No frame will be available until the SVO position is reset. | | INVALID_COORDINATE_SYSTEM | The requested coordinate system is not available. | | INVALID_FIRMWARE | The firmware of the camera is out of date. Update to the latest version. | | INVALID_FUNCTION_PARAMETERS | Invalid parameters have been given for the function. | | CUDA_ERROR | A CUDA error has been detected in the process, in sl.Camera.grab() or sl.Camera.retrieve_xxx() only. Activate verbose in sl.Camera.open() for more info. | | CAMERA_NOT_INITIALIZED | The ZED SDK is not initialized. Probably a missing call to sl.Camera.open(). | | NVIDIA_DRIVER_OUT_OF_DATE | Your NVIDIA driver is too old and not compatible with your current CUDA version. | | INVALID_FUNCTION_CALL | The call of the function is not valid in the current context. Could be a missing call of sl.Camera.open(). | | CORRUPTED_SDK_INSTALLATION | The ZED SDK was not able to load its dependencies or some assets are missing. Reinstall the ZED SDK or check for missing dependencies (cuDNN, TensorRT). | | INCOMPATIBLE_SDK_VERSION | The installed ZED SDK is incompatible with the one used to compile the program. | | INVALID_AREA_FILE | The given area file does not exist. Check the path. | | INCOMPATIBLE_AREA_FILE | The area file does not contain enough data to be used or the sl.DEPTH_MODE used during the creation of the area file is different from the one currently set. | | CAMERA_FAILED_TO_SETUP | Failed to open the camera at the proper resolution. Try another resolution or make sure that the UVC driver is properly installed. | | CAMERA_DETECTION_ISSUE | Your camera can not be opened. Try replugging it to another port or flipping the USB-C connector (if there is one). | | CANNOT_START_CAMERA_STREAM | Cannot start the camera stream. Make sure your camera is not already used by another process or blocked by firewall or antivirus. | | NO_GPU_DETECTED | No GPU found. CUDA is unable to list it. Can be a driver/reboot issue. | | PLANE_NOT_FOUND | Plane not found. Either no plane is detected in the scene, at the location or corresponding to the floor, or the floor plane doesn't match the prior given. | | MODULE_NOT_COMPATIBLE_WITH_CAMERA | The module you try to use is not compatible with your camera sl.MODEL. Note: sl.MODEL.ZED does not has an IMU and does not support the AI modules. | | MOTION_SENSORS_REQUIRED | The module needs the sensors to be enabled (see InitParameters.sensors_required). | | MODULE_NOT_COMPATIBLE_WITH_CUDA_VERSION | The module needs a newer version of CUDA. | | DRIVER_FAILURE | The drivers initialization has failed. When using gmsl cameras, try restarting with sudo systemctl restart zed_x_daemon.service. | | CAMERA_EXCEEDS_BANDWIDTH | The camera configuration exceeds available PHY CSI bandwidth (GMSL). Reduce resolution or FPS, or adjust hardware configuration. | ## Values - `ERROR_CODE.SENSOR_CONFIGURATION_CHANGED` - `ERROR_CODE.POTENTIAL_CALIBRATION_ISSUE` - `ERROR_CODE.CONFIGURATION_FALLBACK` - `ERROR_CODE.SENSORS_DATA_REQUIRED` - `ERROR_CODE.CORRUPTED_FRAME` - `ERROR_CODE.CAMERA_REBOOTING` - `ERROR_CODE.SUCCESS` - `ERROR_CODE.FAILURE` - `ERROR_CODE.NO_GPU_COMPATIBLE` - `ERROR_CODE.NOT_ENOUGH_GPU_MEMORY` - `ERROR_CODE.CAMERA_NOT_DETECTED` - `ERROR_CODE.SENSORS_NOT_INITIALIZED` - `ERROR_CODE.SENSORS_NOT_AVAILABLE` - `ERROR_CODE.INVALID_RESOLUTION` - `ERROR_CODE.LOW_USB_BANDWIDTH` - `ERROR_CODE.CALIBRATION_FILE_NOT_AVAILABLE` - `ERROR_CODE.INVALID_CALIBRATION_FILE` - `ERROR_CODE.INVALID_SVO_FILE` - `ERROR_CODE.SVO_RECORDING_ERROR` - `ERROR_CODE.END_OF_SVOFILE_REACHED` - `ERROR_CODE.SVO_UNSUPPORTED_COMPRESSION` - `ERROR_CODE.INVALID_COORDINATE_SYSTEM` - `ERROR_CODE.INVALID_FIRMWARE` - `ERROR_CODE.INVALID_FUNCTION_PARAMETERS` - `ERROR_CODE.CUDA_ERROR` - `ERROR_CODE.CAMERA_NOT_INITIALIZED` - `ERROR_CODE.NVIDIA_DRIVER_OUT_OF_DATE` - `ERROR_CODE.INVALID_FUNCTION_CALL` - `ERROR_CODE.CORRUPTED_SDK_INSTALLATION` - `ERROR_CODE.INCOMPATIBLE_SDK_VERSION` - `ERROR_CODE.INVALID_AREA_FILE` - `ERROR_CODE.INCOMPATIBLE_AREA_FILE` - `ERROR_CODE.CAMERA_FAILED_TO_SETUP` - `ERROR_CODE.CAMERA_DETECTION_ISSUE` - `ERROR_CODE.CANNOT_START_CAMERA_STREAM` - `ERROR_CODE.NO_GPU_DETECTED` - `ERROR_CODE.PLANE_NOT_FOUND` - `ERROR_CODE.MODULE_NOT_COMPATIBLE_WITH_CAMERA` - `ERROR_CODE.MOTION_SENSORS_REQUIRED` - `ERROR_CODE.MODULE_NOT_COMPATIBLE_WITH_CUDA_VERSION` - `ERROR_CODE.DRIVER_FAILURE` - `ERROR_CODE.CAMERA_EXCEEDS_BANDWIDTH` - `ERROR_CODE.LAST` --- # CameraParameters Class containing the intrinsic parameters of a camera. That information about the camera will be returned by sl.Camera.get_camera_information(). **Note:** Similar to the sl.CalibrationParameters, those parameters are taken from the settings file (SNXXX.conf) and are modified during the sl.Camera.open() call when running a self-calibration). **Note:** Those parameters given after sl.Camera.open() call, represent the camera matrix corresponding to rectified or unrectified images. **Note:** When filled with rectified parameters, fx, fy, cx, cy must be the same for left and right camera once sl.Camera.open() has been called. **Note:** Since distortion is corrected during rectification, distortion should not be considered on rectified images. ## Properties ### `focal_length_metric: float` *(read/write)* Real focal length in millimeters. ### `disto: list[float]` *(read-only)* Distortion factor : [k1, k2, p1, p2, k3, k4, k5, k6, s1, s2, s3, s4]. Radial (k1, k2, k3, k4, k5, k6), Tangential (p1,p2) and Prism (s1, s2, s3, s4) distortion. ### `h_fov: float` *(read/write)* Horizontal field of view, in degrees. ### `cx: float` *(read/write)* Optical center along x axis, defined in pixels (usually close to width / 2). ### `v_fov: float` *(read/write)* Vertical field of view, in degrees. ### `d_fov: float` *(read/write)* Diagonal field of view, in degrees. ### `image_size: Resolution` *(read/write)* Size in pixels of the images given by the camera. ### `fy: float` *(read/write)* Focal length in pixels along y axis. ### `fx: float` *(read/write)* Focal length in pixels along x axis. ### `cy: float` *(read/write)* Optical center along y axis, defined in pixels (usually close to height / 2). ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `set_disto(self, value1: float, value2: float, value3: float, value4: float, value5: float) -> None` Sets the elements of the disto array. :param value1: k1 :param value2: k2 :param value3: p1 :param value4: p2 :param value5: k3 ### `set_up(self, fx_: float, fy_: float, cx_: float, cy_: float) -> None` Setups the parameters of a camera. :param fx_: Horizontal focal length :param fy_: Vertical focal length :param cx_: Horizontal optical center :param cx_: Vertical optical center. ### `scale(self, resolution: Resolution) -> CameraParameters` Return the sl.CameraParameters for another resolution. :param resolution: Resolution in which to get the new sl.CameraParameters. :return: The sl.CameraParameters for the resolution given as input. --- # CalibrationParameters Class containing intrinsic and extrinsic parameters of the camera (translation and rotation). That information about the camera will be returned by sl.Camera.get_camera_information(). **Note:** The calibration/rectification process, called during sl.Camera.open(), is using the raw parameters defined in the SNXXX.conf file, where XXX is the serial number of the camera. **Note:** Those values may be adjusted or not by the self-calibration to get a proper image alignment. **Note:** After sl.Camera.open() is done (with or without self-calibration activated), most of the stereo parameters (except baseline of course) should be 0 or very close to 0. **Note:** It means that images after rectification process (given by sl.Camera.retrieve_image()) are aligned as if they were taken by a "perfect" stereo camera, defined by the new sl.CalibrationParameters. **Warning:** CalibrationParameters are returned in sl.COORDINATE_SYSTEM.IMAGE, they are not impacted by the sl.InitParameters.coordinate_system. ## Properties ### `right_cam: CameraParameters` *(read/write)* Intrinsic sl.CameraParameters of the right camera. ### `stereo_transform: Transform` *(read-only)* Left to right camera transform, expressed in user coordinate system and unit (defined by sl.InitParameters.coordinate_system). ### `left_cam: CameraParameters` *(read/write)* Intrinsic sl.CameraParameters of the left camera. ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `_set(self) -> None` ### `get_camera_baseline(self) -> float` Returns the baseline of the camera in the sl.UNIT defined in sl.InitParameters.coordinate_units. --- # Pose Class containing positional tracking data giving the position and orientation of the camera in 3D space. Different representations of position and orientation can be retrieved, along with timestamp and pose confidence. ## Properties ### `valid: bool` *(read/write)* Whether the tracking is activated or not. **Note:** You should check that first if something is wrong. ### `twist: npt.NDArray[float]` *(read/write)* Twist of the camera available in reference camera. This expresses velocity in free space, broken into its linear and angular parts. ### `pose_confidence: int` *(read/write)* Confidence/quality of the pose estimation for the target frame. A confidence metric of the tracking [0-100] with: - 0: tracking is lost - 100: tracking can be fully trusted ### `pose_covariance: npt.NDArray[float]` *(read/write)* 6x6 pose covariance matrix (NumPy array) of translation (the first 3 values) and rotation in so3 (the last 3 values). **Note:** Computed only if PositionalTrackingParameters.enable_spatial_memory is disabled. ### `timestamp: Timestamp` *(read/write)* sl.Timestamp of the sl.Pose. This timestamp should be compared with the camera timestamp for synchronization. ### `twist_covariance: npt.NDArray[float]` *(read/write)* Row-major representation of the 6x6 twist covariance matrix of the camera. This expresses the uncertainty of the twist. ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `init_pose(self, pose: Pose) -> None` Deep copy from another sl.Pose. :param pose: sl.Pose to copy. ### `init_transform(self, pose_data: Transform, timestamp=0, confidence=0) -> None` Initializes the sl.Pose from a sl.Transform. :param pose_data: sl.Transform containing pose data to copy. :param timestamp: Timestamp of the pose data. :param confidence: Confidence of the pose data. ### `get_translation(self, py_translation=None) -> Translation` Returns the sl.Translation corresponding to the current sl.Pose. :param py_translation: sl.Translation to be returned. It creates one by default. :return: sl.Translation filled with values from the sl.Pose. ### `get_orientation(self, py_orientation=None) -> Orientation` Returns the sl.Orientation corresponding to the current sl.Pose. :param py_orientation: sl.Orientation to be returned. It creates one by default. :return: sl.Orientation filled with values from the sl.Pose. ### `get_rotation_matrix(self, py_rotation=None) -> Rotation` Returns the sl.Rotation corresponding to the current sl.Pose. :param py_rotation: sl.Rotation to be returned. It creates one by default. :return: sl.Rotation filled with values from the sl.Pose. ### `get_rotation_vector(self) -> npt.NDArray[float]` Returns the the 3x1 rotation vector (obtained from 3x3 rotation matrix using Rodrigues formula) corresponding to the current sl.Pose. :param py_rotation: sl.Rotation to be returned. It creates one by default. :return: Rotation vector (NumPy array) created from the sl.Pose values. ### `get_euler_angles(self, radian=True) -> npt.NDArray[float]` Converts the rotation component of the sl.Pose into Euler angles. :param radian: Whether the angle will be returned in radian or degree. Default: True :return: Euler angles (Numpy array) created from the sl.Pose values representing the rotations around the X, Y and Z axes using YZX convention. ### `pose_data(self, pose_data=None) -> Transform` sl.Transform containing the rotation and translation data of the sl.Pose. :param pose_data: sl.Transform to be returned. It creates one by default. :return: sl.Transform containing the rotation and translation data of the sl.Pose. --- # SensorsData Class containing all sensors data (except image sensors) to be used for positional tracking or environment study. **Note:** Some data are not available in SVO and streaming input mode. **Note:** They are specified by a note "Not available in SVO or STREAM mode." in the documentation of a specific data. **Note:** If nothing is mentioned in the documentation, they are available in all input modes. ## Properties ### `camera_moving_state: CAMERA_MOTION_STATE` *(read/write)* Motion state of the camera. ### `image_sync_trigger: int` *(read/write)* Indicates if the sensors data has been taken during a frame capture on sensor. If the value is 1, the data has been retrieved during a left sensor frame acquisition (the time precision is linked to the IMU rate, therefore 800Hz == 1.3ms). If the value is 0, the data has not been taken during a frame acquisition. ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `init_sensorsData(self, sensorsData: SensorsData) -> None` Copy constructor. :param sensorsData: sl.SensorsData object to copy. ### `get_imu_data(self) -> IMUData` Gets the IMU data. :return: sl.IMUData containing the IMU data. ### `get_barometer_data(self) -> BarometerData` Gets the barometer data. :return: sl.BarometerData containing the barometer data. ### `get_magnetometer_data(self) -> MagnetometerData` Gets the magnetometer data. :return: sl.MagnetometerData containing the magnetometer data. ### `get_temperature_data(self) -> TemperatureData` Gets the temperature data. :return: sl.TemperatureData containing the temperature data. --- # PositionalTrackingParameters Class containing a set of parameters for the positional tracking module initialization. The default constructor sets all parameters to their default settings. **Note:** Parameters can be adjusted by the user. ## Properties ### `set_as_static: bool` *(read/write)* Whether to define the camera as static. If true, it will not move in the environment. This allows you to set its position using initial_world_transform. All ZED SDK functionalities requiring positional tracking will be enabled without additional computation. sl.Camera.get_position() will return the value set as initial_world_transform. Default: False ### `set_floor_as_origin: bool` *(read/write)* Initializes the tracking to be aligned with the floor plane to better position the camera in space. Default: False **Note:** This launches floor plane detection in the background until a suitable floor plane is found. **Note:** The tracking will start in sl.POSITIONAL_TRACKING_STATE.SEARCHING state. **Warning:** This features does not work with sl.MODEL.ZED since it needs an IMU to classify the floor. **Warning:** The camera needs to look at the floor during initialization for optimum results. ### `area_file_path: str` *(read/write)* Path of an area localization file that describes the surroundings (saved from a previous tracking session). Default: (empty) **Note:** Loading an area file will start a search phase, during which the camera will try to position itself in the previously learned area. **Warning:** The area file describes a specific location. If you are using an area file describing a different location, the tracking function will continuously search for a position and may not find a correct one. **Warning:** The '.area' file can only be used with the same depth mode (sl.DEPTH_MODE) as the one used during area recording. ### `mode: POSITIONAL_TRACKING_MODE` *(read/write)* Positional tracking mode used. Can be used to improve accuracy in some types of scene at the cost of longer runtime. Default: sl.POSITIONAL_TRACKING_MODE.GEN_3 ### `enable_area_memory: bool` *(read/write)* Whether the camera can remember its surroundings. This helps correct positional tracking drift and can be helpful for positioning different cameras relative to one other in space. Default: true **Warning:** This mode requires more resources to run, but greatly improves tracking accuracy. **Warning:** We recommend leaving it on by default. ### `enable_imu_fusion: bool` *(read/write)* Whether to enable the IMU fusion. When set to False, only the optical odometry will be used. Default: True **Note:** This setting has no impact on the tracking of a camera. **Note:** sl.MODEL.ZED does not have an IMU. ### `enable_localization_only: bool` *(read/write)* Whether to enable the area mode in localize only mode. ### `enable_pose_smoothing: bool` *(read/write)* Whether to enable smooth pose correction for small drift correction. Default: False ### `set_gravity_as_origin: bool` *(read/write)* Whether to override 2 of the 3 rotations from initial_world_transform using the IMU gravity. Default: True **Note:** This parameter does nothing on sl.ZED.MODEL since it does not have an IMU. ### `enable_2d_ground_mode: bool` *(read/write)* Whether to enable 2D localization mode ### `depth_min_range: float` *(read/write)* Minimum depth used by the ZED SDK for positional tracking. It may be useful for example if any steady objects are in front of the camera and may perturb the positional tracking algorithm. Default: -1 (no minimum depth) ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `save(self, filename: str) -> bool` Saves the current set of parameters into a file to be reloaded with the load() method. :param filename: Name of the file which will be created to store the parameters. :return: True if the file was successfully saved, otherwise False. **Warning:** For security reasons, the file must not already exist. **Warning:** In case a file already exists, the method will return False and existing file will not be updated. ### `load(self, filename: str) -> bool` Loads a set of parameters from the values contained in a previously save() "saved" file. :param filename: Path to the file from which the parameters will be loaded. :return: True if the file was successfully loaded, otherwise False. ### `initial_world_transform(self, init_pos=None) -> Transform` Position of the camera in the world frame when the camera is started. Use this sl.Transform to place the camera frame in the world frame. Default: Identity matrix. **Note:** The camera frame (which defines the reference frame for the camera) is by default positioned at the world frame when tracking is started. ### `set_initial_world_transform(self, value: Transform) -> None` Set the position of the camera in the world frame when the camera is started. :param value: Position of the camera in the world frame when the camera will start. --- # RecordingParameters Class containing the options used to record. The default constructor sets all parameters to their default settings. **Note:** Parameters can be adjusted by the user. ## Properties ### `compression_mode: SVO_COMPRESSION_MODE` *(read/write)* Compression mode the recording. Default: sl.SVO_COMPRESSION_MODE.H265 ### `target_framerate: int` *(read/write)* Framerate for the recording file. Default: 0 (camera framerate will be taken) **Warning:** This framerate must be below or equal to the camera framerate and camera framerate must be a multiple of the target framerate. **Warning:** It means that it must respect `` camera_framerate%target_framerate == 0``. **Warning:** Allowed framerates are 15,30, 60 or 100 if possible. **Warning:** Any other values will be discarded and camera FPS will be taken. ### `encoding_preset: SVO_ENCODING_PRESET` *(read/write)* Encoding preset for the hardware encoder. Controls the speed/quality tradeoff of the GPU encoder. Default: SVO_ENCODING_PRESET.DEFAULT **Note:** Only applicable when compression_mode is H264 or H265. ### `encryption_key: str` *(read/write)* Optional encryption key or passphrase to protect the SVO file. When set, the SVO file is AES-256-CTR encrypted on the fly during recording. The same value must be provided in InitParameters.svo_decryption_key for playback. The value is interpreted as follows: - If it points to an existing file containing a 32-byte binary key (or 64 hex characters), it is used as a raw AES-256 key. - If it is a 64-character hexadecimal string, it is used directly as a raw AES-256 key. - Otherwise, it is treated as a passphrase and a key is derived via PBKDF2-SHA256. Default: "" (no encryption) **Note:** Requires OpenSSL (libcrypto) to be available on the system at runtime. ### `transcode_streaming_input: bool` *(read/write)* Defines whether to decode and re-encode a streaming source. Default: False **Note:** If set to False, it will avoid decoding/re-encoding and convert directly streaming input into a SVO file. **Note:** This saves a encoding session and can be especially useful on NVIDIA Geforce cards where the number of encoding session is limited. **Note:** compression_mode, target_framerate and bitrate will be ignored in this mode. ### `bitrate: int` *(read/write)* Overrides the default bitrate of the SVO file, in kbits/s. Default: 0 (the default values associated with the resolution) **Note:** Only works if compression_mode is H264 or H265. **Note:** Available range: 0 or [1000 - 60000] ### `video_filename: str` *(read/write)* Filename of the file to save the recording into. ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # StreamingParameters Class containing the options used to stream with the ZED SDK. The default constructor sets all parameters to their default settings. **Note:** Parameters can be adjusted by the user. ## Properties ### `adaptative_bitrate: bool` *(read/write)* Defines whether the adaptive bitrate is enable. Default: False **Note:** Bitrate will be adjusted depending the number of packet dropped during streaming. **Note:** If activated, the bitrate can vary between [bitrate/4, bitrate]. **Warning:** Currently, the adaptive bitrate only works when "sending" device is a NVIDIA Jetson (X1, X2, Xavier, Nano). ### `target_framerate: int` *(read/write)* Framerate for the streaming output. Default: 0 (camera framerate will be taken) **Warning:** This framerate must be below or equal to the camera framerate. **Warning:** Allowed framerates are 15, 30, 60 or 100 if possible. **Warning:** Any other values will be discarded and camera FPS will be taken. ### `gop_size: int` *(read/write)* GOP size in number of frames. Default: -1 (the GOP size will last at maximum 2 seconds, depending on camera FPS) **Note:** The GOP size determines the maximum distance between IDR/I-frames. Very high GOP size will result in slightly more efficient compression, especially on static scenes. But latency will increase. **Note:** Maximum value: 256 ### `codec: STREAMING_CODEC` *(read/write)* Encoding used for streaming. ### `port: int` *(read/write)* Port used for streaming. **Warning:** Port must be an even number. Any odd number will be rejected. **Warning:** Port must be opened. ### `chunk_size: int` *(read/write)* Size of a single chunk. Default: 16084 **Note:** Stream buffers are divided into X number of chunks where each chunk is chunk_size bytes long. **Note:** You can lower chunk_size value if network generates a lot of packet lost: this will generates more chunk for a single image, but each chunk sent will be lighter to avoid inside-chunk corruption. **Note:** Increasing this value can decrease latency. Note: Available range: [1024 - 65000] ### `bitrate: int` *(read/write)* Defines the streaming bitrate in Kbits/s | STREAMING_CODEC | RESOLUTION | FPS | Bitrate (kbps) | |:---:|:---:|:---:|:---:| | H264 | HD2K | 15 | 8500 | | H264 | HD1080 | 30 | 12500 | | H264 | HD720 | 60 | 7000 | | H265 | HD2K | 15 | 7000 | | H265 | HD1080 | 30 | 11000 | | H265 | HD720 | 60 | 6000 | Default: 0 (it will be set to the best value depending on your resolution/FPS) **Note:** Available range: [1000 - 60000] ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # ObjectDetectionParameters Class containing a set of parameters for the object detection module. The default constructor sets all parameters to their default settings. **Note:** Parameters can be adjusted by the user. ## Properties ### `fused_objects_group_name: str` *(read/write)* In a multi camera setup, specify which group this model belongs to. In a multi camera setup, multiple cameras can be used to detect objects and multiple detector having similar output layout can see the same object. Therefore, Fusion will fuse together the outputs received by multiple detectors only if they are part of the same fused_objects_group_name. **Note:** This parameter is not used when not using a multi-camera setup and must be set in a multi camera setup. ### `prediction_timeout_s: float` *(read/write)* Prediction duration of the ZED SDK when an object is not detected anymore before switching its state to sl.OBJECT_TRACKING_STATE.SEARCHING. It prevents the jittering of the object state when there is a short misdetection. The user can define their own prediction time duration. Default: 0.2 **Note:** During this time, the object will have sl.OBJECT_TRACKING_STATE.OK state even if it is not detected. **Note:** The duration is expressed in seconds. **Warning:** prediction_timeout_s will be clamped to 1 second as the prediction is getting worse with time. **Warning:** Setting this parameter to 0 disables the ZED SDK predictions. ### `enable_segmentation: bool` *(read/write)* Whether the object masks will be computed. Default: False ### `detection_model: OBJECT_DETECTION_MODEL` *(read/write)* sl.OBJECT_DETECTION_MODEL to use. Default: sl.OBJECT_DETECTION_MODEL.MULTI_CLASS_BOX_FAST ### `max_range: float` *(read/write)* Upper depth range for detections. Default: -1 (value set in sl.InitParameters.depth_maximum_distance) **Note:** The value cannot be greater than sl.InitParameters.depth_maximum_distance and its unit is defined in sl.InitParameters.coordinate_units. ### `instance_module_id: int` *(read/write)* Id of the module instance. This is used to identify which object detection module instance is used. ### `batch_parameters: BatchParameters` *(read/write)* Batching system parameters. Batching system (introduced in 3.5) performs short-term re-identification with deep-learning and trajectories filtering. sl.BatchParameters.enable must to be true to use this feature (by default disabled). ### `custom_onnx_file: str` *(read/write)* Path to the YOLO-like onnx file for custom object detection ran in the ZED SDK. When `detection_model` is OBJECT_DETECTION_MODEL::CUSTOM_YOLOLIKE_BOX_OBJECTS, a onnx model must be passed so that the ZED SDK can optimize it for your GPU and run inference on it. The resulting optimized model will be saved for re-use in the future. .. attention:: - The model must be a YOLO-like model. .. attention:: - The caching uses the `custom_onnx_file` string along with your GPU specs to decide whether to use the cached optmized model or to optimize the passed onnx model. If you want to use a different model (i.e. an onnx with different weights), you must use a different `custom_onnx_file` string or delete the cached optimized model in /resources. **Note:** This parameter is useless when detection_model is not OBJECT_DETECTION_MODEL::CUSTOM_YOLOLIKE_BOX_OBJECTS. ### `custom_onnx_dynamic_input_shape: Resolution` *(read/write)* Resolution to the YOLO-like onnx file for custom object detection ran in the ZED SDK. This resolution defines the input tensor size for dynamic shape ONNX model only. The batch and channel dimensions are automatically handled, it assumes it's color images like default YOLO models. **Note:** This parameter is only used when detection_model is OBJECT_DETECTION_MODEL::CUSTOM_YOLOLIKE_BOX_OBJECTS and the provided ONNX file is using dynamic shapes. .. attention:: - Multiple model only support squared images Default: Squared images 512x512 (input tensor will be 1x3x512x512) ### `enable_tracking: bool` *(read/write)* Whether the object detection system includes object tracking capabilities across a sequence of images. Default: True ### `filtering_mode: OBJECT_FILTERING_MODE` *(read/write)* Filtering mode that should be applied to raw detections. Default: sl.OBJECT_FILTERING_MODE.NMS_3D (same behavior as previous ZED SDK version) **Note:** This parameter is only used in detection model sl.OBJECT_DETECTION_MODEL.MULTI_CLASS_BOX_XXX and sl.OBJECT_DETECTION_MODEL.CUSTOM_BOX_OBJECTS. **Note:** For custom object, it is recommended to use sl.OBJECT_FILTERING_MODE.NMS_3D_PER_CLASS or sl.OBJECT_FILTERING_MODE.NONE. **Note:** In this case, you might need to add your own NMS filter before ingesting the boxes into the object detection module. ### `allow_reduced_precision_inference: bool` *(read/write)* Whether to allow inference to run at a lower precision to improve runtime and memory usage. It might increase the initial optimization time and could include downloading calibration data or calibration cache and slightly reduce the accuracy. **Note:** The fp16 is automatically enabled if the GPU is compatible and provides a speed up of almost x2 and reduce memory usage by almost half, no precision loss. **Note:** This setting allow int8 precision which can speed up by another x2 factor (compared to fp16, or x4 compared to fp32) and half the fp16 memory usage, however some accuracy could be lost. **Note:** The accuracy loss should not exceed 1-2% on the compatible models. **Note:** The current compatible models are all sl.AI_MODELS.HUMAN_BODY_XXXX. ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # BodyTrackingParameters Class containing a set of parameters for the body tracking module. The default constructor sets all parameters to their default settings. **Note:** Parameters can be adjusted by the user. ## Properties ### `body_format: BODY_FORMAT` *(read/write)* Body format to be outputted by the ZED SDK with sl.Camera.retrieve_bodies(). Default: sl.BODY_FORMAT.BODY_18 ### `prediction_timeout_s: float` *(read/write)* Prediction duration of the ZED SDK when an object is not detected anymore before switching its state to sl.OBJECT_TRACKING_STATE.SEARCHING. It prevents the jittering of the object state when there is a short misdetection. The user can define their own prediction time duration. Default: 0.2 **Note:** During this time, the object will have sl.OBJECT_TRACKING_STATE.OK state even if it is not detected. **Note:** The duration is expressed in seconds. **Warning:** prediction_timeout_s will be clamped to 1 second as the prediction is getting worse with time. **Warning:** Setting this parameter to 0 disables the ZED SDK predictions. ### `enable_segmentation: bool` *(read/write)* Whether the body/person masks will be computed. Default: False ### `detection_model: BODY_TRACKING_MODEL` *(read/write)* sl.BODY_TRACKING_MODEL to use. Default: sl.BODY_TRACKING_MODEL.HUMAN_BODY_ACCURATE ### `max_range: float` *(read/write)* Upper depth range for detections. Default: -1 (value set in sl.InitParameters.depth_maximum_distance) **Note:** The value cannot be greater than sl.InitParameters.depth_maximum_distance and its unit is defined in sl.InitParameters.coordinate_units. ### `instance_module_id: int` *(read/write)* Id of the module instance. This is used to identify which body tracking module instance is used. ### `enable_tracking: bool` *(read/write)* Whether the body tracking system includes body/person tracking capabilities across a sequence of images. Default: True ### `enable_body_fitting: bool` *(read/write)* Whether to apply the body fitting. Default: False ### `body_selection: BODY_KEYPOINTS_SELECTION` *(read/write)* Selection of keypoints to be outputted by the ZED SDK with sl.Camera.retrieve_bodies(). Default: sl.BODY_KEYPOINTS_SELECTION.FULL ### `allow_reduced_precision_inference: bool` *(read/write)* Whether to allow inference to run at a lower precision to improve runtime and memory usage. It might increase the initial optimization time and could include downloading calibration data or calibration cache and slightly reduce the accuracy. **Note:** The fp16 is automatically enabled if the GPU is compatible and provides a speed up of almost x2 and reduce memory usage by almost half, no precision loss. **Note:** This setting allow int8 precision which can speed up by another x2 factor (compared to fp16, or x4 compared to fp32) and half the fp16 memory usage, however some accuracy could be lost. **Note:** The accuracy loss should not exceed 1-2% on the compatible models. **Note:** The current compatible models are all sl.AI_MODELS.HUMAN_BODY_XXXX. ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # BarometerData Class containing data from the barometer sensor. ## Properties ### `is_available: bool` *(read/write)* Whether the barometer sensor is available in your camera. ### `effective_rate: float` *(read/write)* Realtime data acquisition rate in hertz (Hz). ### `timestamp: Timestamp` *(read/write)* Data acquisition timestamp. ### `relative_altitude: float` *(read/write)* Relative altitude from first camera position (at sl.Camera.open() time). ### `pressure: float` *(read/write)* Ambient air pressure in hectopascal (hPa). ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # BatchParameters Class containing a set of parameters for batch object detection. The default constructor sets all parameters to their default settings. **Note:** Parameters can be adjusted by the user. ## Properties ### `enable: bool` *(read/write)* Whether to enable the batch option in the object detection module. Batch queueing system provides: - deep-learning based re-identification - trajectory smoothing and filtering Default: False **Note:** To activate this option, enable must be set to True. ### `latency: float` *(read/write)* Trajectories will be output in batch with the desired latency in seconds. During this waiting time, re-identification of objects is done in the background. **Note:** Specifying a short latency will limit the search (falling in timeout) for previously seen object ids but will be closer to real time output. **Note:** Specifying a long latency will reduce the change of timeout in re-identification but increase difference with live output. ### `id_retention_time: float` *(read/write)* Max retention time in seconds of a detected object. After this time, the same object will mostly have a different id. ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # Bodies Class containing the results of the body tracking module. The detected bodies/persons are listed in body_list. ## Properties ### `body_format: BODY_FORMAT` *(read/write)* Body format used in sl.BodyTrackingParameters.body_format parameter. ### `body_list: list[BodyData]` *(read/write)* List of detected bodies/persons. ### `is_tracked: bool` *(read/write)* Whether both the body tracking and the world orientation has been setup. Default: False ### `is_new: bool` *(read/write)* Whether object_list has already been retrieved or not. Default: False ### `inference_precision_mode: INFERENCE_PRECISION` *(read/write)* Status of the actual inference precision mode used to detect the bodies/persons. **Note:** It depends on the GPU hardware support, the sl.BodyTrackingParameters.allow_reduced_precision_inference input parameter and the model support. ### `timestamp: Timestamp` *(read/write)* Timestamp corresponding to the frame acquisition. This value is especially useful for the async mode to synchronize the data. ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `get_body_data_from_id(self, py_body_data: BodyData, body_data_id: int) -> bool` Method that looks for a given body id in the current bodies list. :param py_body_data: sl.BodyData to fill if the search succeeded. (Direction: out) :param body_data_id: Id of the sl.BodyData to search. (Direction: in) :return: True if found, otherwise False. --- # BodiesBatch Class containing batched data of a detected bodies/persons from the body tracking module. ## Properties ### `tracking_state: OBJECT_TRACKING_STATE` *(read/write)* Bodies/persons tracking state. ### `head_bounding_boxes_2d: npt.NDArray[int][int][int]` *(read-only)* NumPy array of 2D bounding box of the head for each body/person. **Note:** Expressed in pixels on the original image resolution, ```[0, 0]``` is the top left corner. ### `keypoints: npt.NDArray[float][float][float]` *(read-only)* NumPy array of 3D keypoints for each body/person. **Warning:** In some cases, eg. body partially out of the image or missing depth data, some keypoints can not be detected. They will have non finite values. ### `bounding_boxes_2d: npt.NDArray[int][int][int]` *(read-only)* NumPy array of 2D bounding boxes for each body/person. **Note:** Expressed in pixels on the original image resolution, ```[0, 0]``` is the top left corner. A ------ B | Object | D ------ C ### `id: int` *(read/write)* Id of the batch. ### `keypoints_2d: npt.NDArray[int][int][int]` *(read-only)* NumPy array of 2D keypoints for each body/person. **Warning:** In some cases, eg. body partially out of the image or missing depth data, some keypoints can not be detected. They will have non finite values. ### `keypoint_confidences: npt.NDArray[float][float]` *(read-only)* NumPy array of detection confidences NumPy array for each keypoint for each body/person. **Note:** They can not be lower than the sl.BodyTrackingRuntimeParameters.detection_confidence_threshold. **Warning:** In some cases, eg. body partially out of the image or missing depth data, some keypoints can not be detected. They will have non finite values. ### `head_bounding_boxes: npt.NDArray[float][float][float]` *(read-only)* NumPy array of 3D bounding box of the head for each body/person. **Note:** They are defined in sl.InitParameters.coordinate_units and expressed in sl.RuntimeParameters.measure3D_reference_frame. ### `confidences: npt.NDArray[float]` *(read-only)* NumPy array of confidences for each body/person. ### `timestamps: list[Timestamp]` *(read-only)* List of timestamps for each body/person. ### `head_positions: npt.NDArray[float][float]` *(read-only)* NumPy array of 3D centroid of the head for each body/person. **Note:** They are defined in sl.InitParameters.coordinate_units and expressed in sl.RuntimeParameters.measure3D_reference_frame. ### `velocities: npt.NDArray[float][float]` *(read-only)* NumPy array of 3D velocities for each body/person. ### `positions: npt.NDArray[float][float]` *(read-only)* NumPy array of positions for each body/person. ### `action_states: list[OBJECT_ACTION_STATE]` *(read-only)* List of action states for each body/person. ### `bounding_boxes: npt.NDArray[float][float][float]` *(read-only)* NumPy array of 3D bounding boxes for each body/person. **Note:** They are defined in sl.InitParameters.coordinate_units and expressed in sl.RuntimeParameters.measure3D_reference_frame. 1 ------ 2 / /| 0 ------ 3 | | Object | 6 | |/ 4 ------ 7 ### `position_covariances: npt.NDArray[float][float]` *(read-only)* NumPy array of positions' covariances for each body/person. ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # BodyData Class containing data of a detected body/person such as its bounding_box, id and its 3D position. ## Properties ### `unique_object_id: str` *(read/write)* Unique id to help identify and track AI detections. It can be either generated externally, or by using generate_unique_id() or left empty. ### `keypoint_2d: npt.NDArray[int][int]` *(read-only)* Set of useful points representing the human body in 2D. **Note:** Expressed in pixels on the original image resolution, ```[0, 0]``` is the top left corner. **Warning:** In some cases, eg. body partially out of the image, some keypoints can not be detected. They will have negatives coordinates. ### `action_state: OBJECT_ACTION_STATE` *(read/write)* Body/person action state. ### `position_covariance: npt.NDArray[float]` *(read/write)* Covariance matrix of the 3D position. **Note:** It is represented by its upper triangular matrix value = [p0, p1, p2] [p1, p3, p4] [p2, p4, p5] where pi is ```position_covariance[i]``` ### `dimensions: npt.NDArray[float]` *(read/write)* 3D body/person dimensions: width, height, length. **Note:** It is defined in sl.InitParameters.coordinate_units and expressed in sl.RuntimeParameters.measure3D_reference_frame. ### `local_position_per_joint: npt.NDArray[float][float]` *(read-only)* NumPy array of local position (position of the child keypoint with respect to its parent expressed in its parent coordinate frame) for each keypoint. **Note:** They are expressed in sl.REFERENCE_FRAME.CAMERA or sl.REFERENCE_FRAME.WORLD. **Warning:** Not available with sl.BODY_FORMAT.BODY_18. ### `mask: Mat` *(read/write)* Mask defining which pixels which belong to the body/person (in bounding_box_2d and set to 255) and those of the background (set to 0). **Warning:** The mask information is only available for tracked bodies (sl.OBJECT_TRACKING_STATE.OK) that have a valid depth. **Warning:** Otherwise, the mask will not be initialized (```mask.is_init() == False```). ### `tracking_state: OBJECT_TRACKING_STATE` *(read/write)* Body/person tracking state. ### `bounding_box: npt.NDArray[float][float]` *(read/write)* 3D bounding box of the body/person represented as eight 3D points. **Note:** It is defined in sl.InitParameters.coordinate_units and expressed in sl.RuntimeParameters.measure3D_reference_frame. 1 ------ 2 / /| 0 ------ 3 | | Object | 6 | |/ 4 ------ 7 ### `id: int` *(read/write)* Body/person identification number. It is used as a reference when tracking the body through the frames. **Note:** Only available if sl.BodyTrackingParameters.enable_tracking is activated. **Note:** Otherwise, it will be set to -1. ### `global_root_orientation: npt.NDArray[float]` *(read-only)* Global root orientation of the skeleton (NumPy array). The orientation is also represented by a quaternion. **Note:** The global root position is already accessible in keypoint attribute by using the root index of a given sl.BODY_FORMAT. **Warning:** Not available with sl.BODY_FORMAT.BODY_18. ### `head_bounding_box_2d: npt.NDArray[int][int]` *(read-only)* 2D bounding box of the head of the body/person represented as four 2D points starting at the top left corner and rotation clockwise. **Note:** Expressed in pixels on the original image resolution, ```[0, 0]``` is the top left corner. ### `head_bounding_box: npt.NDArray[float][float]` *(read-only)* 3D bounding box of the head of the body/person represented as eight 3D points. **Note:** It is defined in sl.InitParameters.coordinate_units and expressed in sl.RuntimeParameters.measure3D_reference_frame. ### `confidence: float` *(read/write)* Detection confidence value of the body/person. From 0 to 100, a low value means the body might not be localized perfectly. ### `head_position: npt.NDArray[float]` *(read/write)* 3D centroid of the head of the body/person. **Note:** It is defined in sl.InitParameters.coordinate_units and expressed in sl.RuntimeParameters.measure3D_reference_frame. ### `velocity: npt.NDArray[float]` *(read/write)* Body/person 3D velocity. **Note:** It is defined in ```sl.InitParameters.coordinate_units / s``` and expressed in sl.RuntimeParameters.measure3D_reference_frame. ### `keypoints_covariance: npt.NDArray[float][float]` *(read/write)* NumPy array of detection covariance for each keypoint. **Warning:** In some cases, eg. body partially out of the image or missing depth data, some keypoints can not be detected. Their covariances will be 0. ### `local_orientation_per_joint: npt.NDArray[float][float]` *(read-only)* NumPy array of local orientation for each keypoint. **Note:** The orientation is represented by a quaternion. **Warning:** Not available with sl.BODY_FORMAT.BODY_18. ### `position: npt.NDArray[float]` *(read/write)* Body/person 3D centroid. **Note:** It is defined in sl.InitParameters.coordinate_units and expressed in sl.RuntimeParameters.measure3D_reference_frame. ### `bounding_box_2d: npt.NDArray[int][int]` *(read/write)* 2D bounding box of the body/person represented as four 2D points starting at the top left corner and rotation clockwise. **Note:** Expressed in pixels on the original image resolution, ```[0, 0]``` is the top left corner. A ------ B | Object | D ------ C ### `keypoint: npt.NDArray[float][float]` *(read-only)* Set of useful points representing the human body in 3D. **Note:** They are defined in sl.InitParameters.coordinate_units and expressed in sl.RuntimeParameters.measure3D_reference_frame. **Warning:** In some cases, eg. body partially out of the image or missing depth data, some keypoints can not be detected. They will have non finite values. ### `keypoint_confidence: npt.NDArray[float]` *(read-only)* NumPy array of detection confidences for each keypoint. **Note:** They can not be lower than the sl.BodyTrackingRuntimeParameters.detection_confidence_threshold. **Warning:** In some cases, eg. body partially out of the image or missing depth data, some keypoints can not be detected. They will have non finite values. ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # BodyTrackingFusionParameters Holds the options used to initialize the body tracking module of the Fusion. ## Properties ### `enable_tracking: bool` *(read/write)* Defines if the object detection will track objects across images flow. Default: True ### `enable_body_fitting: bool` *(read/write)* Defines if the body fitting will be applied. Default: False **Note:** If you enable it and the camera provides data as BODY_18 the fused body format will be BODY_34. ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # BodyTrackingFusionRuntimeParameters Holds the options used to change the behavior of the body tracking module at runtime. ## Properties ### `skeleton_minimum_allowed_camera: int` *(read/write)* If a skeleton was detected in less than skeleton_minimum_allowed_camera cameras, it will be discarded. Default: -1. ### `skeleton_minimum_allowed_keypoints: int` *(read/write)* If the fused skeleton has less than skeleton_minimum_allowed_keypoints keypoints, it will be discarded. Default: -1. ### `skeleton_smoothing: float` *(read/write)* This value controls the smoothing of the tracked or fitted fused skeleton. It is ranged from 0 (low smoothing) and 1 (high smoothing). Default: 0. ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # BodyTrackingRuntimeParameters Class containing a set of runtime parameters for the body tracking module. The default constructor sets all parameters to their default settings. **Note:** Parameters can be adjusted by the user. ## Properties ### `minimum_keypoints_threshold: int` *(read/write)* Minimum threshold for the keypoints. The ZED SDK will only output the keypoints of the skeletons with threshold greater than this value. Default: 0 **Note:** It is useful, for example, to remove unstable fitting results when a skeleton is partially occluded. ### `detection_confidence_threshold: float` *(read/write)* Confidence threshold. From 1 to 100, with 1 meaning a low threshold, more uncertain objects and 99 very few but very precise objects. Default: 20 **Note:** If the scene contains a lot of objects, increasing the confidence can slightly speed up the process, since every object instance is tracked. ### `skeleton_smoothing: float` *(read/write)* Control of the smoothing of the fitted fused skeleton. It is ranged from 0 (low smoothing) and 1 (high smoothing). Default: 0 ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # BodyTrackingSensorsParameters Structure containing a set of parameters for the body tracking module in Sensors API. ## Properties ### `body_format: BODY_FORMAT` *(read/write)* Body format to be outputted by the ZED SDK with Camera.retrieve_bodies(). ### `prediction_timeout_s: float` *(read/write)* Prediction duration of the ZED SDK when an object is not detected anymore before switching its state to SEARCHING. It prevents the jittering of the object state when there is a short misdetection. The duration is expressed in seconds. ### `detection_model: BODY_TRACKING_MODEL` *(read/write)* BODY_TRACKING_MODEL to use. ### `enable_segmentation: bool` *(read/write)* Whether the body/person masks will be computed. ### `max_range: float` *(read/write)* Upper depth range for detections. Default: -1.0 (value set in InitParameters.depth_maximum_distance) ### `instance_module_id: int` *(read/write)* Id of the module instance. This is used to identify which body tracking module instance is used. ### `sensors_ids: list[SensorDeviceIdentifier]` *(read/write)* List of sensor id that will be used for this instance. By default empty which means all available sensors in Sensors when the body tracking instance is started. ### `enable_tracking: bool` *(read/write)* Whether the body tracking system includes body/person tracking capabilities across a sequence of images. ### `enable_body_fitting: bool` *(read/write)* Whether to apply the body fitting. ### `allow_reduced_precision_inference: bool` *(read/write)* Whether to allow inference to run at a lower precision to improve runtime and memory usage. It might increase the initial optimization time and could include downloading calibration data or calibration cache and slightly reduce the accuracy. ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `__init__(self, instance_module_id=0, enable_tracking=True, enable_segmentation=False, detection_model=BODY_TRACKING_MODEL.HUMAN_BODY_ACCURATE, enable_body_fitting=False, body_format=BODY_FORMAT.BODY_18, max_range=-1.0, prediction_timeout_s=0.2) -> None` Default constructor. --- # BodyTrackingSensorsRuntimeParameters Structure containing a set of runtime parameters for the body tracking module in Sensors API. ## Properties ### `minimum_keypoints_threshold: int` *(read/write)* Minimum threshold for the keypoints. The ZED SDK will only output the keypoints of the skeletons with threshold greater than this value. Default: 0 ### `detection_confidence_threshold: float` *(read/write)* Confidence threshold. From 1 to 100, with 1 meaning a low threshold, more uncertain objects and 99 very few but very precise objects. Default: 20.0 ### `skeleton_smoothing: float` *(read/write)* Control of the smoothing of the fitted fused skeleton. It is ranged from 0 (low smoothing) and 1 (high smoothing). ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `__init__(self, detection_confidence_threshold=20.0, minimum_keypoints_threshold=0, skeleton_smoothing=0.0) -> None` Default constructor. --- # CameraConfiguration Structure containing information about the camera sensor. Information about the camera is available in the sl.CameraInformation struct returned by sl.Camera.get_camera_information(). **Note:** This object is meant to be used as a read-only container, editing any of its field won't impact the SDK. **Warning:** sl.CalibrationParameters are returned in sl.COORDINATE_SYSTEM.IMAGE, they are not impacted by the sl.InitParameters.coordinate_system. ## Properties ### `firmware_version: int` *(read-only)* Internal firmware version of the camera. ### `resolution: Resolution` *(read-only)* Resolution of the camera. ### `calibration_parameters: CalibrationParameters` *(read-only)* Intrinsics and extrinsic stereo parameters for rectified/undistorted images. ### `fps: float` *(read-only)* FPS of the camera. ### `calibration_parameters_raw: CalibrationParameters` *(read-only)* Intrinsics and extrinsic stereo parameters for unrectified/distorted images. ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # CameraIdentifier Used to identify a specific camera in the Fusion API ## Properties ### `serial_number: int` *(read/write)* Serial number of the camera. ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # CameraInformation Structure containing information of a single camera (serial number, model, calibration, etc.) That information about the camera will be returned by Camera.get_camera_information() **Note:** This object is meant to be used as a read-only container, editing any of its fields won't impact the SDK. **Warning:** CalibrationParameters are returned in COORDINATE_SYSTEM.IMAGE , they are not impacted by the InitParameters.coordinate_system ## Properties ### `sensors_configuration: SensorsConfiguration` *(read-only)* Sensors configuration parameters stored in a sl.SensorsConfiguration. ### `input_type: INPUT_TYPE` *(read-only)* Input type used in the ZED SDK. ### `serial_number: int` *(read-only)* Serial number of the camera. ### `camera_model: MODEL` *(read-only)* Model of the camera (see sl.MODEL). ### `camera_configuration: CameraConfiguration` *(read-only)* Camera configuration parameters stored in a sl.CameraConfiguration. ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # CameraMetrics Holds the metrics of a sender in the fusion process. ## Properties ### `ratio_detection: float` *(read/write)* Skeleton detection percent during the last second. Number of frames with at least one detection / number of frames, over the last second. A low value means few detections occured lately for this sender. ### `is_present: bool` *(read/write)* Is set to false if no data in this batch of metrics. ### `synced_latency: float` *(read/write)* Latency (in seconds) after Fusion synchronization. Difference between the timestamp of the data received and the timestamp at the end of the Fusion synchronization. ### `received_latency: float` *(read/write)* Latency (in second) of the received data. Timestamp difference between the time when the data are sent and the time they are received (mostly introduced when using the local network workflow). ### `delta_ts: float` *(read/write)* Average data acquisition timestamp difference. Average standard deviation of sender's period since the start. ### `received_fps: float` *(read/write)* FPS of the received data. ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # CameraOne This class serves as the primary interface between the camera and the various features provided by the SDK when using Monocular cameras. A standard program will use the Camera class like this: import pyzed.sl as sl def main(): # --- Initialize a Camera object and open the ZED # Create a ZED camera object zed = sl.CameraOne() # Set configuration parameters init_params = sl.InitParametersOne() init_params.camera_resolution = sl.RESOLUTION.HD720 # Use HD720 video mode for USB cameras # init_params.camera_resolution = sl.RESOLUTION.HD1200 # Use HD1200 video mode for GMSL cameras init_params.camera_fps = 60 # Set fps at 60 # Open the camera err = zed.open(init_params) if err != sl.ERROR_CODE.SUCCESS: print(repr(err)) exit(-1) # --- Main loop grabbing images and depth values # Capture 50 frames and stop i = 0 image = sl.Mat() depth = sl.Mat() while i < 50 : # Grab an image if zed.grab() == sl.ERROR_CODE.SUCCESS: # A new image is available if grab() returns SUCCESS # Display a pixel color zed.retrieve_image(image, sl.VIEW.LEFT) # Get the left image err, center_rgb = image.get_value(image.get_width() / 2, image.get_height() / 2) if err == sl.ERROR_CODE.SUCCESS: print("Image ", i, " center pixel R:", int(center_rgb[0]), " G:", int(center_rgb[1]), " B:", int(center_rgb[2])) else: print("Image ", i, " error:", err) i = i+1 # --- Close the Camera zed.close() return 0 if __name__ == "__main__": main() ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `close(self) -> None` Close an opened camera. If open() has been called, this method will close the connection to the camera (or the SVO file) and free the corresponding memory. If open() wasn't called or failed, this method won't have any effect. **Note:** If an asynchronous task is running within the Camera object, like save_area_map(), this method will wait for its completion. **Note:** To apply a new InitParametersOne, you will need to close the camera first and then open it again with the new InitParameters values. **Warning:** Therefore you need to make sure to delete your GPU sl.Mat objects before the context is destroyed. ### `open(self, py_init: InitParametersOne=None) -> ERROR_CODE` Opens the ZED camera from the provided InitParametersOne. The method will also check the hardware requirements and run a self-calibration. :param py_init: A structure containing all the initial parameters. Default: a preset of InitParametersOne. :return: An error code giving information about the internal process. If ERROR_CODE.SUCCESS is returned, the camera is ready to use. Every other code indicates an error and the program should be stopped. Here is the proper way to call this function: zed = sl.CameraOne() # Create a ZED camera object init_params = sl.InitParametersOne() # Set configuration parameters init_params.camera_resolution = sl.RESOLUTION.HD720 # Use HD720 video mode init_params.camera_fps = 60 # Set fps at 60 # Open the camera err = zed.open(init_params) if (err != sl.ERROR_CODE.SUCCESS) : print(repr(err)) # Display the error exit(-1) **Note:** If you are having issues opening a camera, the diagnostic tool provided in the SDK can help you identify to problems. - **Windows:** C:\Program Files (x86)\ZED SDK\tools\ZED Diagnostic.exe - **Linux:** /usr/local/zed/tools/ZED Diagnostic **Note:** If this method is called on an already opened camera, close() will be called. ### `is_opened(self) -> bool` Reports if the camera has been successfully opened. It has the same behavior as checking if open() returns ERROR_CODE.SUCCESS. :return: True if the ZED camera is already setup, otherwise false. ### `grab(self) -> ERROR_CODE` This method will grab the latest images from the camera, rectify them, and compute the retrieve_measure() "measurements" based on the RuntimeParameters provided (depth, point cloud, tracking, etc.) As measures are created in this method, its execution can last a few milliseconds, depending on your parameters and your hardware. The exact duration will mostly depend on the following parameters: - InitParametersOne.camera_resolution : Lower resolutions are faster to compute. This method is meant to be called frequently in the main loop of your application. **Note:** Since ZED SDK 3.0, this method is blocking. It means that grab() will wait until a new frame is detected and available. **Note:** If no new frames is available until timeout is reached, grab() will return ERROR_CODE.CAMERA_NOT_DETECTED since the camera has probably been disconnected. :return: ERROR_CODE.SUCCESS means that no problem was encountered. **Note:** Returned errors can be displayed using ``str()``. image = sl.Mat() while True: # Grab an image if zed.grab() == sl.ERROR_CODE.SUCCESS: # A new image is available if grab() returns SUCCESS zed.retrieve_image(image) # Get the left image # Use the image for your application ### `retrieve_image(self, py_mat, view=VIEW.LEFT, mem_type=MEM.CPU, resolution=None) -> ERROR_CODE` Retrieves images from the camera (or SVO file). Multiple images are available along with a view of various measures for display purposes. Available images and views are listed here. As an example, VIEW.DEPTH can be used to get a gray-scale version of the depth map, but the actual depth values can be retrieved using retrieve_measure() . **Pixels** Most VIEW modes output image with 4 channels as BGRA (Blue, Green, Red, Alpha), for more information see enum VIEW **Memory** By default, images are copied from GPU memory to CPU memory (RAM) when this function is called. If your application can use GPU images, using the **type** parameter can increase performance by avoiding this copy. If the provided sl.Mat object is already allocated and matches the requested image format, memory won't be re-allocated. **Image size** By default, images are returned in the resolution provided by Resolution "get_camera_information().camera_configuration.resolution". However, you can request custom resolutions. For example, requesting a smaller image can help you speed up your application. **Warning:** A sl.Mat resolution higher than the camera resolution **cannot** be requested. :param py_mat: The sl.Mat to store the image. (Direction: out) :param view: Defines the image you want (see VIEW). Default: VIEW.LEFT. (Direction: in) :param mem_type: Defines on which memory the image should be allocated. Default: MEM.CPU (you cannot change this default value). (Direction: in) :param resolution: If specified, defines the Resolution of the output sl.Mat. If set to Resolution "Resolution(0,0)", the camera resolution will be taken. Default: (0,0). (Direction: in) :return: ERROR_CODE.SUCCESS if the method succeeded. :return: ERROR_CODE.INVALID_FUNCTION_PARAMETERS if the view mode requires a module not enabled (VIEW.DEPTH with DEPTH_MODE.NONE for example). :return: ERROR_CODE.FAILURE if another error occurred. **Note:** As this method retrieves the images grabbed by the grab() method, it should be called afterward. # create sl.Mat objects to store the images left_image = sl.Mat() while True: # Grab an image if zed.grab() == sl.ERROR_CODE.SUCCESS: # A new image is available if grab() returns SUCCESS zed.retrieve_image(left_image, sl.VIEW.LEFT) # Get the rectified left image # Display the center pixel colors err, left_center = left_image.get_value(left_image.get_width() / 2, left_image.get_height() / 2) if err == sl.ERROR_CODE.SUCCESS: print("left_image center pixel R:", int(left_center[0]), " G:", int(left_center[1]), " B:", int(left_center[2])) else: print("error:", err) ### `retrieve_tensor(self, dest, params) -> None` Retrieved a sl::Tensor, containing the input image pre-processed for inference with SVO or live camera. This method provides a way to obtain the pre-processed input image in a format suitable for deep learning inference tasks. The retrieved Tensor is allocated on the GPU, allowing for efficient processing and integration with deep learning frameworks. The pre-processing steps applied to the input image include resizing, normalization, and any other transformations required to prepare the image for inference. This method is particularly useful when working with deep learning models that require specific input formats and pre-processing steps. By retrieving the pre-processed Tensor directly from the Camera class, users can streamline their workflow and ensure compatibility with their deep learning pipelines. **Note:** This method requires that the camera has been opened in either LIVE mode, SVO mode or STREAM mode. **Note:** The retrieved Tensor is allocated on the GPU, so ensure that your system has sufficient GPU memory to accommodate the Tensor size. :param dest: The Tensor to store the pre-processed input image for inference. :param params: Options to configure the pre-processing steps applied to the input image. :return: ERROR_CODE "ERROR_CODE::SUCCESS" if the method succeeded. :return: ERROR_CODE "ERROR_CODE::INVALID_FUNCTION_PARAMETERS" if the provided params are invalid. :return: ERROR_CODE "ERROR_CODE::CAMERA_NOT_INITIALIZED" if the camera is not opened. :return: ERROR_CODE "ERROR_CODE::FAILURE" if another error occurred. ### `get_camera_settings_range(self, settings: VIDEO_SETTINGS) -> None` Get the range for the specified camera settings VIDEO_SETTINGS as min/max value. :param settings: Must be set at a valid VIDEO_SETTINGS that accepts a min/max range and available for the current camera model. :param min: The minimum value that can be reached to be fill. :param max: The maximum value that can be reached to be fill. :return: ERROR_CODE to indicate if the method was successful. ### `get_svo_position_at_timestamp(self, timestamp) -> None` Retrieves the frame index within the SVO file corresponding to the provided timestamp. \param timestamp The target timestamp for which the frame index is to be determined. :return: The frame index within the SVO file that aligns with the given timestamp. Returns -1 if the timestamp falls outside the bounds of the SVO file. ### `set_svo_position(self, position) -> ERROR_CODE` Sets the playback cursor to the desired position in the SVO file. This method allows you to move around within a played-back SVO file. After calling, the next call to grab() will read the provided position. :param position: The position in the SVO file. :return: An error code stating the success, or not. **Note:** The method works only if the camera is open in SVO playback mode. import pyzed.sl as sl def main(): # Create a ZED camera object zed = sl.CameraOne() # Set configuration parameters init_params = sl.InitParametersOne() init_params.set_from_svo_file("path/to/my/file.svo") # Open the camera err = zed.open(init_params) if err != sl.ERROR_CODE.SUCCESS: print(repr(err)) exit(-1) # Loop between frames 0 and 50 left_image = sl.Mat() while zed.get_svo_position() < zed.get_svo_number_of_frames() - 1: print("Current frame: ", zed.get_svo_position()) # Loop if we reached frame 50 if zed.get_svo_position() == 50: err = zed.set_svo_position(0) if err != sl.ERROR_CODE.SUCCESS: print(repr(err)) exit(-1) # Grab an image if zed.grab() == sl.ERROR_CODE.SUCCESS: zed.retrieve_image(left_image, sl.VIEW.LEFT) # Get the rectified left image # Use the image in your application # Close the Camera zed.close() return 0 if __name__ == "__main__" : main() ### `get_svo_position(self) -> int` Returns the current playback position in the SVO file. The position corresponds to the number of frames already read from the SVO file, starting from 0 to n. Each grab() call increases this value by one (except when using InitParametersOne.svo_real_time_mode). :return: The current frame position in the SVO file. -1 if the SDK is not reading an SVO. **Note:** The method works only if the camera is open in SVO playback mode. See set_svo_position() for an example. ### `get_svo_number_of_frames(self) -> int` Returns the number of frames in the SVO file. :return: The total number of frames in the SVO file. -1 if the SDK is not reading a SVO. The method works only if the camera is open in SVO playback mode. ### `ingest_data_into_svo(self, data: SVOData) -> ERROR_CODE` ingest a SVOData in the SVO file. :return: An error code stating the success, or not. The method works only if the camera is open in SVO recording mode. ### `get_svo_data_keys(self) -> list` Get the external channels that can be retrieved from the SVO file. :return: a list of keys The method works only if the camera is open in SVO playback mode. ### `retrieve_svo_data(self, key: str, data: dict, ts_begin: Timestamp, ts_end: Timestamp) -> ERROR_CODE` retrieve SVO datas from the SVO file at the given channel key and in the given timestamp range. :return: An error code stating the success, or not. :param key: The channel key. :param data: The dict to be filled with SVOData objects, with timestamps as keys. :param ts_begin: The beginning of the range. :param ts_end: The end of the range. The method works only if the camera is open in SVO playback mode. ### `set_camera_settings(self, settings: VIDEO_SETTINGS, value=-1) -> ERROR_CODE` Sets the value of the requested VIDEO_SETTINGS "camera setting" (gain, brightness, hue, exposure, etc.). This method only applies for VIDEO_SETTINGS that require a single value. Possible values (range) of each settings are available here. :param settings: The setting to be set. :param value: The value to set. Default: auto mode :return: ERROR_CODE to indicate if the method was successful. **Warning:** Setting VIDEO_SETTINGS.EXPOSURE or VIDEO_SETTINGS.GAIN to default will automatically sets the other to default. **Note:** The method works only if the camera is open in LIVE or STREAM mode. # Set the gain to 50 zed.set_camera_settings(sl.VIDEO_SETTINGS.GAIN, 50) ### `set_camera_settings_range(self, settings: VIDEO_SETTINGS, value_min=-1, value_max=-1) -> ERROR_CODE` Sets the value of the requested VIDEO_SETTINGS "camera setting" that supports two values (min/max). This method only works with the following VIDEO_SETTINGS: - sl.VIDEO_SETTINGS.AUTO_EXPOSURE_TIME_RANGE - sl.VIDEO_SETTINGS.AUTO_ANALOG_GAIN_RANGE - sl.VIDEO_SETTINGS.AUTO_DIGITAL_GAIN_RANGE :param settings: The setting to be set. :param min: The minimum value that can be reached (-1 or 0 gives full range). :param max: The maximum value that can be reached (-1 or 0 gives full range). :return: ERROR_CODE to indicate if the method was successful. **Warning:** If VIDEO_SETTINGS settings is not supported or min >= max, it will return ERROR_CODE.INVALID_FUNCTION_PARAMETERS. **Note:** The method works only if the camera is open in LIVE or STREAM mode. # For ZED X based product, set the automatic exposure from 2ms to 5ms. Expected exposure time cannot go beyond those values zed.set_camera_settings_range(sl.VIDEO_SETTINGS.AEC_RANGE, 2000, 5000); ### `set_camera_settings_roi(self, settings: VIDEO_SETTINGS, roi: Rect, reset=False) -> ERROR_CODE` Overloaded method for VIDEO_SETTINGS.AEC_AGC_ROI which takes a Rect as parameter. :param settings: Must be set at VIDEO_SETTINGS.AEC_AGC_ROI, otherwise the method will have no impact. :param roi: Rect that defines the target to be applied for AEC/AGC computation. Must be given according to camera resolution. :param reset: Cancel the manual ROI and reset it to the full image. Default: False **Note:** The method works only if the camera is open in LIVE or STREAM mode. roi = sl.Rect(42, 56, 120, 15) zed.set_camera_settings_roi(sl.VIDEO_SETTINGS.AEC_AGC_ROI, roi) ### `get_camera_settings(self, setting: VIDEO_SETTINGS) -> tuple[ERROR_CODE, int]` Returns the current value of the requested VIDEO_SETTINGS "camera setting" (gain, brightness, hue, exposure, etc.). Possible values (range) of each setting are available here. :param setting: The requested setting. :return: ERROR_CODE to indicate if the method was successful. :return: The current value for the corresponding setting. err, gain = zed.get_camera_settings(sl.VIDEO_SETTINGS.GAIN) if err == sl.ERROR_CODE.SUCCESS: print("Current gain value:", gain) else: print("error:", err) **Note:** The method works only if the camera is open in LIVE or STREAM mode. **Note:** Settings are not exported in the SVO file format. ### `get_camera_settings_range(self, setting: VIDEO_SETTINGS) -> tuple[ERROR_CODE, int, int]` Returns the values of the requested settings for VIDEO_SETTINGS that supports two values (min/max). This method only works with the following VIDEO_SETTINGS: - sl.VIDEO_SETTINGS.AUTO_EXPOSURE_TIME_RANGE - sl.VIDEO_SETTINGS.AUTO_ANALOG_GAIN_RANGE - sl.VIDEO_SETTINGS.AUTO_DIGITAL_GAIN_RANGE Possible values (range) of each setting are available here. :param setting: The requested setting. :return: ERROR_CODE to indicate if the method was successful. :return: The current value of the minimum for the corresponding setting. :return: The current value of the maximum for the corresponding setting. err, aec_range_min, aec_range_max = zed.get_camera_settings(sl.VIDEO_SETTINGS.AUTO_EXPOSURE_TIME_RANGE) if err == sl.ERROR_CODE.SUCCESS: print("Current AUTO_EXPOSURE_TIME_RANGE range values ==> min:", aec_range_min, "max:", aec_range_max) else: print("error:", err) **Note:** Works only with ZED X that supports low-level controls ### `get_camera_settings_roi(self, setting: VIDEO_SETTINGS, roi: Rect) -> ERROR_CODE` Returns the current value of the currently used ROI for the camera setting AEC_AGC_ROI. :param setting: Must be set at VIDEO_SETTINGS.AEC_AGC_ROI, otherwise the method will have no impact. (Direction: in) :param roi: Roi that will be filled. (Direction: out) :return: ERROR_CODE to indicate if the method was successful. roi = sl.Rect() err = zed.get_camera_settings_roi(sl.VIDEO_SETTINGS.AEC_AGC_ROI, roi) print("Current ROI for AEC_AGC: " + str(roi.x) + " " + str(roi.y)+ " " + str(roi.width) + " " + str(roi.height)) **Note:** Works only if the camera is open in LIVE or STREAM mode with VIDEO_SETTINGS.AEC_AGC_ROI. **Note:** It will return ERROR_CODE.INVALID_FUNCTION_CALL or ERROR_CODE.INVALID_FUNCTION_PARAMETERS otherwise. ### `is_camera_setting_supported(self, setting: VIDEO_SETTINGS) -> bool` Returns if the video setting is supported by the camera or not :param setting: the video setting to test (Direction: in) :return: True if the VIDEO_SETTINGS is supported by the camera, False otherwise ### `get_current_fps(self) -> float` Returns the current framerate at which the grab() method is successfully called. The returned value is based on the difference of camera get_timestamp() "timestamps" between two successful grab() calls. :return: The current SDK framerate **Warning:** The returned framerate (number of images grabbed per second) can be lower than InitParametersOne.camera_fps if the grab() function runs slower than the image stream or is called too often. current_fps = zed.get_current_fps() print("Current framerate: ", current_fps) ### `get_timestamp(self, time_reference: TIME_REFERENCE) -> Timestamp` Returns the timestamp in the requested TIME_REFERENCE. - When requesting the TIME_REFERENCE.IMAGE timestamp, the UNIX nanosecond timestamp of the latest grab() "grabbed" image will be returned. This value corresponds to the time at which the entire image was available in the PC memory. As such, it ignores the communication time that corresponds to 2 or 3 frame-time based on the fps (ex: 33.3ms to 50ms at 60fps). - When requesting the TIME_REFERENCE.CURRENT timestamp, the current UNIX nanosecond timestamp is returned. This function can also be used when playing back an SVO file. :param time_reference: The selected TIME_REFERENCE. :return: The Timestamp in nanosecond. 0 if not available (SVO file without compression). **Note:** As this function returns UNIX timestamps, the reference it uses is common across several Camera instances. This can help to organized the grabbed images in a multi-camera application. last_image_timestamp = zed.get_timestamp(sl.TIME_REFERENCE.IMAGE) current_timestamp = zed.get_timestamp(sl.TIME_REFERENCE.CURRENT) print("Latest image timestamp: ", last_image_timestamp.get_nanoseconds(), "ns from Epoch.") print("Current timestamp: ", current_timestamp.get_nanoseconds(), "ns from Epoch.") ### `get_frame_dropped_count(self) -> int` Returns the number of frames dropped since grab() was called for the first time. A dropped frame corresponds to a frame that never made it to the grab method. This can happen if two frames were extracted from the camera when grab() is called. The older frame will be dropped so as to always use the latest (which minimizes latency). :return: The number of frames dropped since the first grab() call. ### `get_camera_information(self, resizer=None) -> CameraOneInformation` Not implemented. Returns the CameraInformation associated the camera being used. To ensure accurate calibration, it is possible to specify a custom resolution as a parameter when obtaining scaled information, as calibration parameters are resolution-dependent. When reading an SVO file, the parameters will correspond to the camera used for recording. :param resizer: You can specify a size different from the default image size to get the scaled camera information. Default = (0,0) meaning original image size (given by CameraConfiguration.resolution "get_camera_information().camera_configuration.resolution"). :return: CameraInformation containing the calibration parameters of the ZED, as well as serial number and firmware version. **Warning:** The returned parameters might vary between two execution due to the InitParametersOne.camera_disable_self_calib "self-calibration" being run in the open() method. **Note:** The calibration file SNXXXX.conf can be found in: - **Windows:** C:/ProgramData/Stereolabs/settings/ - **Linux:** /usr/local/zed/settings/. ### `get_init_parameters(self) -> InitParametersOne` Returns the InitParametersOne associated with the Camera object. It corresponds to the structure given as argument to open() method. :return: InitParametersOne containing the parameters used to initialize the Camera object. ### `get_streaming_parameters(self) -> StreamingParameters` Returns the StreamingParameters used. It corresponds to the structure given as argument to the enable_streaming() method. :return: StreamingParameters containing the parameters used for streaming initialization. ### `get_sensors_data(self, py_sensor_data, time_reference=TIME_REFERENCE.CURRENT) -> ERROR_CODE` Retrieves the SensorsData (IMU, magnetometer, barometer) at a specific time reference. - Calling get_sensors_data with TIME_REFERENCE.CURRENT gives you the latest sensors data received. Getting all the data requires to call this method at 800Hz in a thread. - Calling get_sensors_data with TIME_REFERENCE.IMAGE gives you the sensors data at the time of the latest image grab() "grabbed". SensorsData object contains the previous IMUData structure that was used in ZED SDK v2.X: For IMU data, the values are provided in 2 ways :
  • **Time-fused** pose estimation that can be accessed using: * IMUData.get_pose "data.get_imu_data().get_pose()"
  • **Raw values** from the IMU sensor: * IMUData.get_angular_velocity "data.get_imu_data().get_angular_velocity()", corresponding to the gyroscope * IMUData.get_linear_acceleration "data.get_imu_data().get_linear_acceleration()", corresponding to the accelerometer both the gyroscope and accelerometer are synchronized.
  • The delta time between previous and current values can be calculated using data.imu.timestamp **Note:** The IMU quaternion (fused data) is given in the specified COORDINATE_SYSTEM of InitParametersOne. :param py_sensor_data: The SensorsData variable to store the data. (Direction: out) :param reference_frame: Defines the reference from which you want the data to be expressed. Default: REFERENCE_FRAME.WORLD. (Direction: in) :return: ERROR_CODE.SUCCESS if sensors data have been extracted. :return: ERROR_CODE.SENSORS_NOT_AVAILABLE if the camera model is a MODEL.ZED. :return: ERROR_CODE.MOTION_SENSORS_REQUIRED if the camera model is correct but the sensors module is not opened. :return: ERROR_CODE.INVALID_FUNCTION_PARAMETERS if the **reference_time** is not valid. See Warning. **Warning:** In SVO reading mode, the TIME_REFERENCE.CURRENT is currently not available (yielding ERROR_CODE.INVALID_FUNCTION_PARAMETERS. **Warning:** Only the quaternion data and barometer data (if available) at TIME_REFERENCE.IMAGE are available. Other values will be set to 0. ### `get_sensors_data_batch(self, py_sensor_data) -> ERROR_CODE` Retrieves all SensorsData (IMU only) associated to most recent grabbed frame in the specified COORDINATE_SYSTEM of InitParameters. For IMU data, the values are provided in 2 ways:
  • **Time-fused** pose estimation that can be accessed using: * IMUData.get_pose "data.get_imu_data().get_pose()"
  • **Raw values** from the IMU sensor: * IMUData.get_angular_velocity "data.get_imu_data().get_angular_velocity()", corresponding to the gyroscope * IMUData.get_linear_acceleration "data.get_imu_data().get_linear_acceleration()", corresponding to the accelerometer both the gyroscope and accelerometer are synchronized.
  • The delta time between previous and current values can be calculated using data.imu.timestamp :param py_sensor_data: The SensorsData list to store the data. (Direction: out) :return: ERROR_CODE.SUCCESS if sensors data have been extracted. :return: ERROR_CODE.SENSORS_NOT_AVAILABLE if the camera model is a MODEL.ZED. :return: ERROR_CODE.MOTION_SENSORS_REQUIRED if the camera model is correct but the sensors module is not opened. :return: ERROR_CODE.INVALID_FUNCTION_PARAMETERS if the **reference_time** is not valid. See Warning. if zed.grab() == sl.ERROR_CODE.SUCCESS: sensors_data = [] if (zed.get_sensors_data_batch(sensors_data) == sl.ERROR_CODE.SUCCESS): for data in sensors_data: print("IMU data: ", data.imu.get_angular_velocity(), data.imu.get_linear_acceleration()) print("IMU pose: ", data.imu.get_pose().get_translation()) print("IMU orientation: ", data.imu.get_orientation().get()) ### `enable_streaming(self, streaming_parameters=None) -> ERROR_CODE` Creates a streaming pipeline. :param streaming_parameters: A structure containing all the specific parameters for the streaming. Default: a reset of StreamingParameters . :return: ERROR_CODE.SUCCESS if the streaming was successfully started. :return: ERROR_CODE.INVALID_FUNCTION_CALL if open() was not successfully called before. :return: ERROR_CODE.FAILURE if streaming RTSP protocol was not able to start. :return: ERROR_CODE.NO_GPU_COMPATIBLE if the streaming codec is not supported (in this case, use H264 codec which is supported on all NVIDIA GPU the ZED SDK supports). import pyzed.sl as sl def main() : # Create a ZED camera object zed = sl.CameraOneOne() # Set initial parameters init_params = sl.InitParametersOne() init_params.camera_resolution = sl.RESOLUTION.HD720 # Use HD720 video mode (default fps: 60) # Open the camera err = zed.open(init_params) if err != sl.ERROR_CODE.SUCCESS : print(repr(err)) exit(-1) # Enable streaming stream_params = sl.StreamingParameters() stream_params.port = 30000 stream_params.bitrate = 8000 err = zed.enable_streaming(stream_params) if err != sl.ERROR_CODE.SUCCESS : print(repr(err)) exit(-1) # Grab data during 500 frames i = 0 while i < 500 : if zed.grab() == sl.ERROR_CODE.SUCCESS : i = i+1 zed.disable_streaming() zed.close() return 0 if __name__ == "__main__" : main() ### `disable_streaming(self) -> None` Disables the streaming initiated by enable_streaming(). **Note:** This method will automatically be called by close() if enable_streaming() was called. See enable_streaming() for an example. ### `is_streaming_enabled(self) -> bool` Tells if the streaming is running. :return: True if the stream is running, False otherwise. ### `enable_recording(self, record: RecordingParameters) -> ERROR_CODE` Creates an SVO file to be filled by enable_recording() and disable_recording(). SVO files are custom video files containing the un-rectified images from the camera along with some meta-data like timestamps or IMU orientation (if applicable). They can be used to simulate a live ZED and test a sequence with various SDK parameters. Depending on the application, various compression modes are available. See SVO_COMPRESSION_MODE. :param record: A structure containing all the specific parameters for the recording such as filename and compression mode. Default: a reset of RecordingParameters . :return: An ERROR_CODE that defines if the SVO file was successfully created and can be filled with images. **Warning:** This method can be called multiple times during a camera lifetime, but if **video_filename** is already existing, the file will be erased. import pyzed.sl as sl def main() : # Create a ZED camera object zed = sl.CameraOneOne() # Set initial parameters init_params = sl.InitParametersOne() init_params.camera_resolution = sl.RESOLUTION.HD720 # Use HD720 video mode (default fps: 60) init_params.coordinate_units = sl.UNIT.METER # Set units in meters # Open the camera err = zed.open(init_params) if (err != sl.ERROR_CODE.SUCCESS): print(repr(err)) exit(-1) # Enable video recording record_params = sl.RecordingParameters("myVideoFile.svo") err = zed.enable_recording(record_params) if (err != sl.ERROR_CODE.SUCCESS): print(repr(err)) exit(-1) # Grab data during 500 frames i = 0 while i < 500 : # Grab a new frame if zed.grab() == sl.ERROR_CODE.SUCCESS: # Record the grabbed frame in the video file i = i + 1 zed.disable_recording() print("Video has been saved ...") zed.close() return 0 if __name__ == "__main__" : main() ### `disable_recording(self) -> None` Disables the recording initiated by enable_recording() and closes the generated file. **Note:** This method will automatically be called by close() if enable_recording() was called. See enable_recording() for an example. ### `get_recording_status(self) -> RecordingStatus` Get the recording information. :return: The recording state structure. For more details, see RecordingStatus. ### `pause_recording(self, value=True) -> None` Pauses or resumes the recording. :param status: If True, the recording is paused. If False, the recording is resumed. ### `get_device_list() -> list[DeviceProperties]` List all the connected devices with their associated information. This method lists all the cameras available and provides their serial number, models and other information. :return: The device properties for each connected camera. ### `set_timestamp_clock(clock) -> None` Sets the clock source used for all SDK timestamps (images and sensors). This is a process-wide setting shared by all Camera and CameraOne instances. :param clock: The desired TIMESTAMP_CLOCK. **Note:** Call this before opening any camera. ### `get_timestamp_clock() -> TIMESTAMP_CLOCK` Returns the clock source currently used for SDK timestamps. :return: The active TIMESTAMP_CLOCK. ### `set_max_system_clock_step_ms(limit_ms: float) -> None` Sets the maximum system-clock step (ms) the SDK follows per sample when the host clock is adjusted backward. Only meaningful in SYSTEM_CLOCK mode. See sl.set_max_system_clock_step_ms for the full cheat sheet. ### `get_max_system_clock_step_ms() -> float` Returns the current system-clock step clamp in milliseconds. ### `get_streaming_device_list() -> list[StreamingProperties]` Lists all the streaming devices with their associated information. :return: The streaming properties for each connected camera. **Warning:** This method takes around 2 seconds to make sure all network informations has been captured. Make sure to run this method in a thread. ### `reboot(sn: int, full_reboot: bool=True) -> ERROR_CODE` Performs a hardware reset of the ZED 2 and the ZED 2i. :param sn: Serial number of the camera to reset, or 0 to reset the first camera detected. :param full_reboot: Perform a full reboot (sensors and video modules) if True, otherwise only the video module will be rebooted. :return: ERROR_CODE "ERROR_CODE::SUCCESS" if everything went fine. :return: ERROR_CODE "ERROR_CODE::CAMERA_NOT_DETECTED" if no camera was detected. :return: ERROR_CODE "ERROR_CODE::FAILURE" otherwise. **Note:** This method only works for ZED 2, ZED 2i, and newer camera models. **Warning:** This method will invalidate any sl.Camera object, since the device is rebooting. ### `reboot_from_input(input_type: INPUT_TYPE) -> ERROR_CODE` Performs a hardware reset of all devices matching the InputType. :param input_type: Input type of the devices to reset. :return: ERROR_CODE "ERROR_CODE::SUCCESS" if everything went fine. :return: ERROR_CODE "ERROR_CODE::CAMERA_NOT_DETECTED" if no camera was detected. :return: ERROR_CODE "ERROR_CODE::FAILURE" otherwise. :return: ERROR_CODE "ERROR_CODE::INVALID_FUNCTION_PARAMETERS" for SVOs and streams. **Warning:** This method will invalidate any sl.Camera object, since the device is rebooting. --- # CameraOneConfiguration Structure containing information about the camera sensor. Information about the camera is available in the sl.CameraInformation struct returned by sl.Camera.get_camera_information(). **Note:** This object is meant to be used as a read-only container, editing any of its field won't impact the SDK. **Warning:** sl.CalibrationOneParameters are returned in sl.COORDINATE_SYSTEM.IMAGE, they are not impacted by the sl.InitParametersOne.coordinate_system. ## Properties ### `firmware_version: int` *(read-only)* Internal firmware version of the camera. ### `resolution: Resolution` *(read-only)* Resolution of the camera. ### `calibration_parameters: CameraParameters` *(read-only)* Intrinsics and extrinsic stereo parameters for rectified/undistorted images. ### `fps: float` *(read-only)* FPS of the camera. ### `calibration_parameters_raw: CameraParameters` *(read-only)* Intrinsics and extrinsic stereo parameters for unrectified/distorted images. ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # CameraOneInformation Structure containing information of a single camera (serial number, model, calibration, etc.) That information about the camera will be returned by CameraOne.get_camera_information() **Note:** This object is meant to be used as a read-only container, editing any of its fields won't impact the SDK. **Warning:** CalibrationParameters are returned in COORDINATE_SYSTEM.IMAGE , they are not impacted by the InitParametersOne.coordinate_system ## Properties ### `sensors_configuration: SensorsConfiguration` *(read-only)* Sensors configuration parameters stored in a sl.SensorsConfiguration. ### `input_type: INPUT_TYPE` *(read-only)* Input type used in the ZED SDK. ### `serial_number: int` *(read-only)* Serial number of the camera. ### `camera_model: MODEL` *(read-only)* Model of the camera (see sl.MODEL). ### `camera_configuration: CameraOneConfiguration` *(read-only)* Camera configuration parameters stored in a sl.CameraOneConfiguration. ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # Chunk Class representing a sub-mesh containing local vertices and triangles. Vertices and normals have the same size and are linked by id stored in triangles. **Note:** uv contains data only if your mesh have textures (by loading it or after calling sl.Mesh.apply_texture()). ## Properties ### `vertices: npt.NDArray[float]` *(read-only)* NumPy array of vertices. Vertices are defined by a 3D point ```[x, y, z]```. ### `has_been_updated: bool` *(read-only)* Whether the chunk has been updated by an inner process. ### `barycenter: npt.NDArray[float]` *(read-only)* 3D centroid of the chunk. ### `normals: npt.NDArray[float]` *(read-only)* NumPy array of normals. Normals are defined by three components ```[nx, ny, nz]```. **Note:** A normal is defined for each vertex. ### `timestamp: int` *(read-only)* Timestamp of the latest update. ### `colors: npt.NDArray[int]` *(read-only)* NumPy array of colors. Colors are defined by three components ```[r, g, b]```. **Note:** A color is defined for each vertex. ### `triangles: npt.NDArray[int]` *(read-only)* NumPy array of triangles/faces. Triangle defined as a set of three vertices indexes ```[v1, v2, v3]```. ### `uv: npt.NDArray[float]` *(read-only)* UVs defines the 2D projection of each vertices onto the texture. Values are normalized [0, 1] and start from the bottom left corner of the texture (as requested by OpenGL). In order to display a textured mesh you need to bind the texture and then draw each triangle by picking its uv values. **Note:** Contains data only if your mesh has textures (by loading it or calling sl.Mesh.apply_texture()). ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `clear(self) -> None` Clears all data. --- # CommunicationParameters Holds the communication parameter to configure the connection between senders and receiver ## Properties ### `port: int` *(read-only)* The comm port used for streaming the data ### `ip_address: str` *(read-only)* The IP address of the sender ### `comm_type: COMM_TYPE` *(read-only)* The type of the used communication ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `set_for_shared_memory(self) -> None` Setup the communication to used shared memory for intra process workflow, senders and receiver in different threads. ### `set_for_local_network(self, port: int, ip: str='') -> None` Setup local Network connection information --- # CustomBoxObjectData Class that store externally detected objects. The objects can be ingested with sl.Camera.ingest_custom_box_objects() to extract 3D and tracking information over time. ## Properties ### `unique_object_id: str` *(read/write)* Unique id to help identify and track AI detections. It can be either generated externally, or by using generate_unique_id() or left empty. ### `tracking_max_dist: float` *(read/write)* Maximum tracking distance threshold (in meters) before dropping the tracked object when unseen for this amount of meters. By default, do not discard tracked object based on distance. Only valid for static object. ### `prediction_timeout_s: float` *(read/write)* Duration to keep predicting a track's position after occlusion. ### `is_static: bool` *(read/write)* Provide hypothesis about the object staticity to improve the object tracking. - true: the object will be assumed to never move nor being moved. - false: the object will be assumed to be able to move or being moved. ### `tracking_timeout: float` *(read/write)* Maximum tracking time threshold (in seconds) before dropping the tracked object when unseen for this amount of time. By default, let the tracker decide internally based on the internal sub class of the tracked object. ### `min_confirmation_time_s: float` *(read/write)* Minimum confirmation time in seconds required to validate a track. ### `min_velocity_threshold: float` *(read/write)* Threshold to force an object's velocity to zero. ### `bounding_box_2d: npt.NDArray[int][int]` *(read/write)* 2D bounding box of the object represented as four 2D points starting at the top left corner and rotation clockwise. **Note:** Expressed in pixels on the original image resolution, ```[0, 0]``` is the top left corner. A ------ B | Object | D ------ C ### `velocity_smoothing_factor: float` *(read/write)* Control the smoothing of the velocity estimation. Values between 0.0 and 1.0. ### `max_allowed_acceleration: float` *(read/write)* Manually override the acceleration preset. If set, this value takes precedence over the selected preset, allowing for a custom maximum acceleration. Unit is m/s^2. ### `is_grounded: bool` *(read/write)* Provide hypothesis about the object movements (degrees of freedom or DoF) to improve the object tracking. - true: 2 DoF projected alongside the floor plane. Case for object standing on the ground such as person, vehicle, etc. The projection implies that the objects cannot be superposed on multiple horizontal levels. - false: 6 DoF (full 3D movements are allowed). **Note:** This parameter cannot be changed for a given object tracking id. **Note:** It is advised to set it by labels to avoid issues. ### `label: int` *(read/write)* Object label. This information is passed-through and can be used to improve object tracking. **Note:** It should define an object class. This means that any similar object (in classification) should share the same label number. ### `probability: float` *(read/write)* Detection confidence value of the object. **Note:** The value should be in ```[0-1]```. **Note:** It can be used to improve the object tracking. ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # CustomMaskObjectData Class storing externally detected objects. The objects can be ingested with sl.Camera.ingest_custom_mask_objects() to extract 3D and tracking information over time. ## Properties ### `unique_object_id: str` *(read/write)* Unique id to help identify and track AI detections. It can be either generated externally, or by using generate_unique_id() or left empty. ### `tracking_max_dist: float` *(read/write)* Maximum tracking distance threshold (in meters) before dropping the tracked object when unseen for this amount of meters. By default, do not discard tracked object based on distance. Only valid for static object. ### `prediction_timeout_s: float` *(read/write)* Duration to keep predicting a track's position after occlusion. Unit is s. ### `is_static: bool` *(read/write)* Provide hypothesis about the object staticity to improve the object tracking. - true: the object will be assumed to never move nor being moved. - false: the object will be assumed to be able to move or being moved. ### `tracking_timeout: float` *(read/write)* Maximum tracking time threshold (in seconds) before dropping the tracked object when unseen for this amount of time. By default, let the tracker decide internally based on the internal sub class of the tracked object. ### `min_confirmation_time_s: float` *(read/write)* Minimum confirmation time in seconds required to validate a track. Unit is s. ### `min_velocity_threshold: float` *(read/write)* Threshold to force an object's velocity to zero. Unit is m/s. ### `bounding_box_2d: npt.NDArray[int][int]` *(read/write)* 2D bounding box of the object represented as four 2D points starting at the top left corner and rotation clockwise. **Note:** Expressed in pixels on the original image resolution, ```[0, 0]``` is the top left corner. A ------ B | Object | D ------ C ### `velocity_smoothing_factor: float` *(read/write)* Control the smoothing of the velocity estimation. Values between 0.0 and 1.0. ### `max_allowed_acceleration: float` *(read/write)* Manually override the acceleration preset. If set, this value takes precedence over the selected preset, allowing for a custom maximum acceleration. Unit is m/s^2. ### `is_grounded: bool` *(read/write)* Provide hypothesis about the object movements (degrees of freedom or DoF) to improve the object tracking. - true: 2 DoF projected alongside the floor plane. Case for object standing on the ground such as person, vehicle, etc. The projection implies that the objects cannot be superposed on multiple horizontal levels. - false: 6 DoF (full 3D movements are allowed). **Note:** This parameter cannot be changed for a given object tracking id. **Note:** It is advised to set it by labels to avoid issues. ### `label: int` *(read/write)* Object label. This information is passed-through and can be used to improve object tracking. **Note:** It should define an object class. This means that any similar object (in classification) should share the same label number. ### `box_mask: Mat` *(read/write)* Mask defining which pixels which belong to the object (in bounding_box_2d and set to 255) and those of the background (set to 0). ### `probability: float` *(read/write)* Detection confidence value of the object. **Note:** The value should be in ```[0-1]```. **Note:** It can be used to improve the object tracking. ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # CustomObjectDetectionProperties Class containing tracking parameters for object detection. Used to configure how objects are tracked over time. ## Properties ### `prediction_timeout_s: float` *(read/write)* Duration to keep predicting a track's position after occlusion. When an object is no longer visible (occluded or out of frame), the tracker will predict its position for this duration before deleting the track. - Short (e.g., 0.2s): Prevents "ghost" objects but may break tracks during short occlusions. - Long (e.g., 2.0s): Maintains ID during long occlusions but may report objects that are gone. Unit is s. ### `tracking_max_dist: float` *(read/write)* Maximum tracking distance threshold (in meters) before dropping the tracked object when unseen for this amount of meters. By default, do not discard tracked object based on distance. Only valid for static object. ### `min_box_width_normalized: float` *(read/write)* Minimum allowed width normalized to the image size. Any prediction smaller than that will be filtered out. Default: -1 (no filtering) ### `tracking_timeout: float` *(read/write)* Maximum tracking time threshold (in seconds) before dropping the tracked object when unseen for this amount of time. By default, let the tracker decide internally based on the internal sub class of the tracked object. ### `native_mapped_class: OBJECT_SUBCLASS` *(read/write)* For increased accuracy, the native sl::OBJECT_SUBCLASS mapping, if any. Native objects have refined internal parameters for better 3D projection and tracking accuracy. If one of the custom objects can be mapped to one the native sl::OBJECT_SUBCLASS, this can help to boost the tracking accuracy. Default: no mapping ### `min_confirmation_time_s: float` *(read/write)* Minimum confirmation time required to validate a track. The minimum duration (in seconds) an object must be continuously detected before it is reported as a valid track. Helps filter out spurious false positives that appear only briefly. A negative value (e.g. -1) lets the ZED SDK interpret the prediction_timeout_s. Default: -1 ### `max_box_width_meters: float` *(read/write)* Maximum allowed 3D width. Any prediction bigger than that will be either discarded (if object is tracked and in SEARCHING state) or clamped. Default: -1 (no filtering) ### `min_box_width_meters: float` *(read/write)* Minimum allowed 3D width. Any prediction smaller than that will be either discarded (if object is tracked and in SEARCHING state) or clamped. Default: -1 (no filtering) ### `max_allowed_acceleration: float` *(read/write)* Manually override the acceleration preset. If set, this value takes precedence over the selected preset, allowing for a custom maximum acceleration. Unit is m/s^2. ### `object_acceleration_preset: OBJECT_ACCELERATION_PRESET` *(read/write)* Preset defining the expected maximum acceleration of the tracked object. Determines how the ZED SDK interprets object acceleration, affecting tracking behavior and predictions. Default: Default ### `max_box_height_normalized: float` *(read/write)* Maximum allowed height normalized to the image size. Any prediction bigger than that will be filtered out. Default: -1 (no filtering) ### `max_box_width_normalized: float` *(read/write)* Maximum allowed width normalized to the image size. Any prediction bigger than that will be filtered out. Default: -1 (no filtering) ### `velocity_smoothing_factor: float` *(read/write)* Control the smoothing of the velocity estimation. Values between 0.0 and 1.0. - High value (closer to 1.0): Very smooth, but may lag behind rapid changes. - Low value (closer to 0.0): Very responsive to velocity changes, but may be jittery. - 0.5: ZED SDK base tuning. Balanced smoothing and responsiveness. ### `object_tracking_parameters: ObjectTrackingParametersProxy` *(read/write)* Object tracking parameters for this class. Returns a proxy object that allows direct modification of tracking settings. Example: props.object_tracking_parameters.velocity_smoothing_factor = 0.65 ### `is_static: bool` *(read/write)* Provide hypothesis about the object staticity to improve the object tracking. - true: the object will be assumed to never move nor being moved. - false: the object will be assumed to be able to move or being moved. ### `enabled: bool` *(read/write)* Whether the object object is kept or not ### `min_velocity_threshold: float` *(read/write)* Threshold to force an object's velocity to zero. If the calculated speed (m/s) is below this threshold, the object is considered static. This helps eliminate drift on stationary objects. Unit is m/s. ### `min_box_height_normalized: float` *(read/write)* Minimum allowed height normalized to the image size. Any prediction smaller than that will be filtered out. Default: -1 (no filtering) ### `max_box_height_meters: float` *(read/write)* Maximum allowed 3D height. Any prediction bigger than that will be either discarded (if object is tracked and in SEARCHING state) or clamped. Default: -1 (no filtering) ### `min_box_height_meters: float` *(read/write)* Minimum allowed 3D height. Any prediction smaller than that will be either discarded (if object is tracked and in SEARCHING state) or clamped. Default: -1 (no filtering) ### `is_grounded: bool` *(read/write)* Provide hypothesis about the object movements (degrees of freedom or DoF) to improve the object tracking. - true: 2 DoF projected alongside the floor plane. Case for object standing on the ground such as person, vehicle, etc. The projection implies that the objects cannot be superposed on multiple horizontal levels. - false: 6 DoF (full 3D movements are allowed). **Note:** This parameter cannot be changed for a given object tracking id. **Note:** It is advised to set it by labels to avoid issues. ### `detection_confidence_threshold: float` *(read/write)* Confidence threshold. From 1 to 100, with 1 meaning a low threshold, more uncertain objects and 99 very few but very precise objects. Default: 20.f **Note:** If the scene contains a lot of objects, increasing the confidence can slightly speed up the process, since every object instance is tracked. ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # CustomObjectDetectionRuntimeParameters Class containing a set of runtime parameters for the object detection module using your own model ran by the SDK. The default constructor sets all parameters to their default settings. **Note:** Parameters can be adjusted by the user. ## Properties ### `object_class_detection_properties: dict` *(read/write)* Per class object detection properties. ### `object_detection_properties: CustomObjectDetectionProperties` *(read/write)* Global object detection properties. **Note:** object_detection_properties is used as a fallback when sl::CustomObjectDetectionRuntimeParameters.object_class_detection_properties is partially set. ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # DeviceProperties Class containing information about the properties of a camera. **Note:** A camera_model sl.MODEL.ZED_M with an id '-1' can be due to an inverted USB-C cable. ## Properties ### `id: int` *(read/write)* Id of the camera. Default: -1 ### `sensor_address_right: int` *(read/write)* sensor_address when available (ZED-X HDR/XOne HDR only) ### `input_type: INPUT_TYPE` *(read/write)* Input type of the camera. ### `serial_number: int` *(read/write)* Serial number of the camera. Default: 0 **Warning:** Not provided for Windows. ### `i2c_port: int` *(read/write)* i2c port of the camera. ### `gmsl_port: int` *(read/write)* GMSL port of the camera. ### `camera_name: str` *(read/write)* Name of Camera in DT (ZED_CAM1) ### `camera_sensor_model: str` *(read/write)* Name of sensor (zedx) ### `path: str` *(read/write)* System path of the camera. ### `identifier: np.numpy[np.uint8]` *(read/write)* sensor_address when available (ZED-X HDR/XOne HDR only) ### `camera_model: MODEL` *(read/write)* Model of the camera. ### `camera_state: CAMERA_STATE` *(read/write)* State of the camera. Default: sl.CAMERA_STATE.NOT_AVAILABLE ### `camera_badge: str` *(read/write)* Badge name (zedx_ar0234) ### `sensor_address_left: int` *(read/write)* sensor_address when available (ZED-X HDR/XOne HDR only) ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # ECEF Represents a world position in ECEF format. ## Properties ### `x: double` *(read/write)* x coordinate of ECEF. ### `y: double` *(read/write)* y coordinate of ECEF. ### `z: double` *(read/write)* z coordinate of ECEF. ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # ENU Represent a world position in ENU format. ## Properties ### `up: double` *(read/write)* Up parameter ### `north: double` *(read/write)* North parameter ### `east: double` *(read/write)* East parameter ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # FusedPointCloud Class representing a fused point cloud and containing the geometric and color data of the scene captured by the spatial mapping module. By default the fused point cloud is defined as a set of point cloud chunks. This way we update only the required data, avoiding a time consuming remapping process every time a small part of the sl.FusedPointCloud cloud is changed. ## Properties ### `vertices: npt.NDArray[float]` *(read-only)* NumPy array of vertices. Vertices are defined by a colored 3D point ```[x, y, z, rgba]```. ### `normals: npt.NDArray[float]` *(read-only)* NumPy array of normals. Normals are defined by three components ```[nx, ny, nz]```. **Note:** A normal is defined for each vertex. ### `chunks: list[PointCloudChunk]` *(read-only)* List of chunks constituting the sl.FusedPointCloud. ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `save(self, filename: str, typeMesh=MESH_FILE_FORMAT.OBJ, id=[]) -> bool` Saves the current sl.FusedPointCloud into a file. :param filename: Path of the file to store the fused point cloud in. :param typeMesh: File extension type. Default: sl.MESH_FILE_FORMAT.OBJ. :param id: Set of chunks to be saved. Default: (empty) (all chunks are saved) :return: True if the file was successfully saved, otherwise False. **Note:** This method operates on the sl.FusedPointCloud not on chunks. **Note:** This way you can save different parts of your sl.FusedPointCloud by updating it with update_from_chunklist(). ### `load(self, filename: str, update_chunk_only=False) -> bool` Loads the fused point cloud from a file. :param filename: Path of the file to load the fused point cloud from. :param update_chunk_only: Whether to only load data in chunks (and not vertices / normals). Default: False. :return: True if the mesh was successfully loaded, otherwise False. **Note:** Updating a sl.FusedPointCloud is time consuming. Consider using only chunks for better performances. ### `clear(self) -> None` Clears all the data. ### `update_from_chunklist(self, id=[]) -> None` Updates vertices and normals from chunk data pointed by the given list of id. :param id: Indices of chunks which will be concatenated. Default: (empty). **Note:** If the given list of id is empty, all chunks will be used to update the current sl.FusedPointCloud. ### `get_number_of_points(self) -> int` Computes the total number of points stored in all chunks. :return: The number of points stored in all chunks. --- # FusedPositionalTrackingStatus Lists the different status of the positional tracking ## Properties ### `gnss_mode: GNSS_MODE` *(read/write)* Represents the current mode of GNSS. ### `spatial_memory_status: SPATIAL_MEMORY_STATUS` *(read/write)* Represents the current state of camera tracking in the global map. ### `gnss_status: GNSS_STATUS` *(read/write)* Represents the current status of GNSS. ### `odometry_status: ODOMETRY_STATUS` *(read/write)* Represents the current state of Visual-Inertial Odometry (VIO) tracking between the previous frame and the current frame. ### `tracking_fusion_status: POSITIONAL_TRACKING_FUSION_STATUS` *(read/write)* Represents the current state of positional tracking fusion. ### `gnss_fusion_status: GNSS_FUSION_STATUS` *(read/write)* Represents the current state of GNSS fusion for global localization. ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # Fusion Holds Fusion process data and functions ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `init(self, init_fusion_parameters: InitFusionParameters) -> FUSION_ERROR_CODE` Initialize the fusion module with the requested parameters. :param init_parameters: Initialization parameters. :return: ERROR_CODE.SUCCESS if it goes as it should, otherwise it returns an ERROR_CODE. ### `close(self) -> None` Will deactivate all the fusion modules and free internal data. ### `subscribe(self, uuid: CameraIdentifier, communication_parameters: CommunicationParameters, pose: Transform, override_gravity: bool=False) -> FUSION_ERROR_CODE` Set the specified camera as a data provider. :param uuid: The requested camera identifier. :param communication_parameters: The communication parameters to connect to the camera. :param pose: The World position of the camera, regarding the other camera of the setup. :param override_gravity: Indicates the behavior of the fusion with respect to given calibration pose. * If true : The calibration pose directly specifies the camera's absolute pose relative to a global reference frame. * If false : The calibration pose (Pose_rel) is defined relative to the camera's IMU rotational pose. To determine the true absolute position, the Fusion process will compute Pose_abs = Pose_rel * Rot_IMU_camera. * set to false by default :return: FUSION_ERROR_CODE.SUCCESS if it goes as it should, otherwise it returns an FUSION_ERROR_CODE. ### `unsubscribe(self, uuid: CameraIdentifier) -> FUSION_ERROR_CODE` Remove the specified camera from data provider. :param uuid: The requested camera identifier. :return: FUSION_ERROR_CODE.SUCCESS if it goes as it should, otherwise it returns an FUSION_ERROR_CODE. ### `update_pose(self, uuid: CameraIdentifier, pose: Transform) -> FUSION_ERROR_CODE` Updates the specified camera position inside fusion WORLD. :param uuid: The requested camera identifier. :param pose: The World position of the camera, regarding the other camera of the setup. :return: FUSION_ERROR_CODE.SUCCESS if it goes as it should, otherwise it returns an FUSION_ERROR_CODE. ### `get_process_metrics(self) -> tuple[FUSION_ERROR_CODE, FusionMetrics]` Get the metrics of the Fusion process, for the fused data as well as individual camera provider data. :param metrics: The process metrics. :return: FUSION_ERROR_CODE.SUCCESS if it goes as it should, otherwise it returns an FUSION_ERROR_CODE. :return: The process metrics. ### `get_sender_state(self) -> dict` Returns the state of each connected data senders. :return: The individual state of each connected senders. ### `process(self) -> FUSION_ERROR_CODE` Runs the main function of the Fusion, this trigger the retrieve and synchronization of all connected senders and updates the enabled modules. :return: FUSION_ERROR_CODE.SUCCESS if it goes as it should, otherwise it returns an FUSION_ERROR_CODE. ### `enable_body_tracking(self, params: BodyTrackingFusionParameters) -> FUSION_ERROR_CODE` Enables the body tracking fusion module. :param params: Structure containing all specific parameters for body tracking fusion. :return: FUSION_ERROR_CODE.SUCCESS if it goes as it should, otherwise it returns an FUSION_ERROR_CODE. ### `retrieve_bodies(self, bodies: Bodies, parameters: BodyTrackingFusionRuntimeParameters, uuid: CameraIdentifier=CameraIdentifier(0), reference_frame: FUSION_REFERENCE_FRAME=FUSION_REFERENCE_FRAME.BASELINK) -> FUSION_ERROR_CODE` Retrieves the body data, can be the fused data (default), or the raw data provided by a specific sender. :param bodies: The fused bodies will be saved into this objects. :param parameters: Body detection runtime settings, can be changed at each detection. :param uuid: The id of the sender. :param reference_frame: The reference frame in which the objects will be expressed. Default: FUSION_REFERENCE_FRAME "FUSION_REFERENCE_FRAME::BASELINK". :return: FUSION_ERROR_CODE.SUCCESS if it goes as it should, otherwise it returns an FUSION_ERROR_CODE. ### `enable_object_detection(self, params=None) -> FUSION_ERROR_CODE` Enables the object detection fusion module. :param params: Structure containing all specific parameters for object detection fusion. For more information, see the ObjectDetectionFusionParameters documentation. :return: SUCCESS if it goes as it should, otherwise it returns an FUSION_ERROR_CODE. ### `retrieve_objects_all_od_groups(self, objs, reference_frame: FUSION_REFERENCE_FRAME=FUSION_REFERENCE_FRAME.BASELINK) -> FUSION_ERROR_CODE` Retrieves all the fused objects data. :param objs: The fused objects will be saved into this dictionary of objects. :param reference_frame: The reference frame in which the objects will be expressed. Default: FUSION_REFERENCE_FRAME "FUSION_REFERENCE_FRAME::BASELINK". :return: SUCCESS if it goes as it should, otherwise it returns a FUSION_ERROR_CODE. ### `retrieve_objects_one_od_group(self, objs, fused_od_group_name, reference_frame: FUSION_REFERENCE_FRAME=FUSION_REFERENCE_FRAME.BASELINK) -> FUSION_ERROR_CODE` Retrieves the fused objects of a given fused OD group. :param objs: The fused objects will be saved into this objects. :param fused_od_group_name: The name of the fused objects group to retrieve. :param reference_frame: The reference frame in which the objects will be expressed. Default: FUSION_REFERENCE_FRAME "FUSION_REFERENCE_FRAME::BASELINK". :return: SUCCESS if it goes as it should, otherwise it returns a FUSION_ERROR_CODE. ### `retrieve_raw_objects_all_ids(self, objs, uuid) -> FUSION_ERROR_CODE` Retrieves all the raw objects data provided by a specific sender. :param objs: The fused objects will be saved into this dictionary of objects. :param uuid: Retrieve the raw data provided by this sender. ### `retrieve_raw_objects_one_id(self, py_objects, uuid, instance_id) -> FUSION_ERROR_CODE` Retrieves the raw objects data provided by a specific sender and a specific instance id. :param objs: The fused objects will be saved into this objects. :param uuid: Retrieve the raw data provided by this sender. :param instance_id: Retrieve the objects inferred by the model with this ID only. :return: SUCCESS if it goes as it should, otherwise it returns a FUSION_ERROR_CODE. ### `disable_objects_detection(self) -> None` Disable the body fusion tracking module. ### `retrieve_image(self, mat, uuid, resolution=None) -> FUSION_ERROR_CODE` Returns the current sl.VIEW.LEFT of the specified camera, the data is synchronized. :param mat: the CPU BGRA image of the requested camera. :param resolution: the requested resolution of the output image, can be lower or equal (default) to the original image resolution. :param uuid: If set to a sender serial number (different from 0), this will retrieve the raw data provided by this sender. :return: FUSION_ERROR_CODE.SUCCESS if it goes as it should, otherwise it returns an FUSION_ERROR_CODE. ### `retrieve_measure(self, mat, uuid, measure: MEASURE, resolution=None, reference_frame: FUSION_REFERENCE_FRAME=FUSION_REFERENCE_FRAME.BASELINK) -> FUSION_ERROR_CODE` Returns the current measure of the specified camera, the data is synchronized. :param mat: the CPU data of the requested camera. :param uuid: The id of the sender. :param measure: measure: the requested measure type, by default DEPTH (F32_C1). :param resolution: the requested resolution of the output image, can be lower or equal (default) to the original image resolution. :param reference_frame: The reference frame in which the objects will be expressed. Default: FUSION_REFERENCE_FRAME "FUSION_REFERENCE_FRAME::BASELINK". :return: FUSION_ERROR_CODE.SUCCESS if it goes as it should, otherwise it returns an FUSION_ERROR_CODE. ### `disable_body_tracking(self) -> None` Disable the body fusion tracking module. ### `enable_positionnal_tracking(self, parameters: PositionalTrackingFusionParameters) -> FUSION_ERROR_CODE` Enables positional tracking fusion module. :param parameters: A structure containing all the PositionalTrackingFusionParameters that define positional tracking fusion module. :return: FUSION_ERROR_CODE.SUCCESS if it goes as it should, otherwise it returns an FUSION_ERROR_CODE. ### `ingest_gnss_data(self, gnss_data: GNSSData) -> FUSION_ERROR_CODE` Ingest GNSS data from an external sensor into the fusion module. :param gnss_data: The current GNSS data to combine with the current positional tracking data. :return: FUSION_ERROR_CODE.SUCCESS if it goes as it should, otherwise it returns an FUSION_ERROR_CODE. ### `get_position(self, camera_pose: Pose, reference_frame: REFERENCE_FRAME=REFERENCE_FRAME.WORLD, uuid: CameraIdentifier=CameraIdentifier(), position_type: POSITION_TYPE=POSITION_TYPE.FUSION) -> POSITIONAL_TRACKING_STATE` Get the Fused Position referenced to the first camera subscribed. If uuid is specified then project position on the referenced camera. :param camera_pose: Will contain the fused position referenced by default in world (world is given by the calibration of the cameras system). :param reference_frame: Defines the reference from which you want the pose to be expressed. Default : REFERENCE_FRAME.WORLD. :param uuid: If set to a sender serial number (different from 0), this will retrieve position projected on the requested camera if position_type is equal to POSITION_TYPE.FUSION or raw sender position if position_type is equal to POSITION_TYPE.RAW. :param position_type: Select if the position should the fused position re-projected in the camera with uuid or if the position should be the raw position (without fusion) of camera with uui. :return: POSITIONAL_TRACKING_STATE is the current state of the tracking process. ### `get_fused_positional_tracking_status(self) -> FusedPositionalTrackingStatus` Get the current status of fused position. :return: FusedPositionalTrackingStatus is the current status of fused position. ### `get_current_gnss_data(self, gnss_data: GNSSData) -> POSITIONAL_TRACKING_STATE` Returns the last synchronized gnss data. :param out: Last synchronized gnss data. (Direction: out) :return: POSITIONAL_TRACKING_STATE is the current state of the tracking process. ### `get_geo_pose(self, pose: GeoPose) -> GNSS_FUSION_STATUS` Returns the current GeoPose. :param pose: The current GeoPose. (Direction: out) :return: GNSS_FUSION_STATUS is the current state of the tracking process. ### `geo_to_camera(self, input: LatLng, output: Pose) -> GNSS_FUSION_STATUS` Convert latitude / longitude into position in sl::Fusion coordinate system. :param input: The latitude / longitude to be converted in sl::Fusion coordinate system. (Direction: in) :param out: Converted position in sl.Fusion coordinate system. (Direction: out) :return: GNSS_FUSION_STATUS is the current state of the tracking process. ### `camera_to_geo(self, input: Pose, output: GeoPose) -> GNSS_FUSION_STATUS` Convert a position in sl.Fusion coordinate system in global world coordinate. :param pose: Position to convert in global world coordinate. (Direction: in) :param pose: Converted position in global world coordinate. (Direction: out) :return: GNSS_FUSION_STATUS is the current state of the tracking process. ### `get_current_timestamp(self) -> Timestamp` Return the current fusion timestamp, aligned with the synchronized GNSS and camera data. :return: current fusion timestamp. ### `disable_positionnal_tracking(self) -> None` Disable the fusion positional tracking module. The positional tracking is immediately stopped. If a file path is given, saveAreaMap(area_file_path) will be called asynchronously. See getAreaExportState() to get the exportation state. ### `ENU_to_geo(self, input: ENU, output: LatLng) -> FUSION_ERROR_CODE` Convert ENU to LatLng Concert an ENU position into LatLng ### `geo_to_ENU(self, input: LatLng, out: ENU) -> FUSION_ERROR_CODE` Convert LatLng to ENU Convert am LatLng to ENU ### `get_current_gnss_calibration_std(self) -> tuple[GNSS_FUSION_STATUS, float, npt.NDArray]` Get the current calibration uncertainty obtained during calibration process. :return: sl.GNSS_FUSION_STATUS representing current initialisation status. :return: Output yaw uncertainty. :return: Output position uncertainty. # ### `get_geo_tracking_calibration(self) -> Transform` Get the calibration found between VIO and GNSS. :return: sl.Transform is the calibration found between VIO and GNSS during calibration process. # ### `enable_spatial_mapping(self, parameters) -> FUSION_ERROR_CODE` Initializes and starts the spatial mapping processes. The spatial mapping will create a geometric representation of the scene based on both tracking data and 3D point clouds. The resulting output can be a Mesh or a FusedPointCloud. It can be be obtained by calling retrieve_spatial_map_async(). Note that retrieve_spatial_map_async() should be called after request_spatial_map_async(). \param parameters The structure containing all the specific parameters for the spatial mapping. Default: a balanced parameter preset between geometric fidelity and output file size. For more information, see the SpatialMappingParameters documentation. :return: SUCCESS if everything went fine, FUSION_ERROR_CODE "FUSION_ERROR_CODE::FAILURE" otherwise. **Note:** The tracking (enable_positional_tracking()) needs to be enabled to use the spatial mapping. **Note:** Lower SpatialMappingParameters.range_meter and SpatialMappingParameters.resolution_meter for higher performance. **Warning:** This fuction is only available for INTRA_PROCESS communication type. ### `request_spatial_map_async(self) -> None` Starts the spatial map generation process in a non blocking thread from the spatial mapping process. The spatial map generation can take a long time depending on the mapping resolution and covered area. This function will trigger the generation of a mesh without blocking the program. You can get info about the current generation using get_spatial_map_request_status_async(), and retrieve the mesh using request_spatial_map_async(...) . **Note:** Only one mesh can be generated at a time. If the previous mesh generation is not over, new calls of the function will be ignored. # ### `get_spatial_map_request_status_async(self) -> FUSION_ERROR_CODE` Returns the spatial map generation status. This status allows to know if the mesh can be retrieved by calling retrieve_spatial_map_async(). :return: SUCCESS if the mesh is ready and not yet retrieved, otherwise FUSION_ERROR_CODE "FUSION_ERROR_CODE::FAILURE". See request_spatial_map_async() for an example. # ### `retrieve_spatial_map_async(self, py_mesh) -> FUSION_ERROR_CODE` Retrieves the current generated spatial map. After calling request_spatial_map_async(), this method allows you to retrieve the generated mesh or fused point cloud. The Mesh or FusedPointCloud will only be available when get_spatial_map_request_status_async() returns FUSION_ERROR_CODE.SUCCESS. :param py_mesh: The Mesh or FusedPointCloud to be filled with the generated spatial map. (Direction: out) :return: FUSION_ERROR_CODE.SUCCESS if the mesh is retrieved, otherwise FUSION_ERROR_CODE.FAILURE. **Note:** This method only updates the necessary chunks and adds the new ones in order to improve update speed. **Warning:** You should not modify the mesh / fused point cloud between two calls of this method, otherwise it can lead to a corrupted mesh / fused point cloud. See request_spatial_map_async() for an example. ### `disable_spatial_mapping(self) -> None` Disables the spatial mapping process. The spatial mapping is immediately stopped. If the mapping has been enabled, this function will automatically be called by close(). **Note:** This function frees the memory allocated for the spatial mapping, consequently, the spatial map cannot be retrieved after this call. --- # FusionConfiguration Useful struct to store the Fusion configuration, can be read from /write to a JSON file. ## Properties ### `communication_parameters: CommunicationParameters` *(read/write)* The communication parameters to connect this camera to the Fusion. ### `override_gravity: bool` *(read/write)* Indicates the behavior of the fusion with respect to given calibration pose. - If true : The calibration pose directly specifies the camera's absolute pose relative to a global reference frame. - If false : The calibration pose (Pose_rel) is defined relative to the camera's IMU rotational pose. To determine the true absolute position, the Fusion process will compute Pose_abs = Pose_rel * Rot_IMU_camera. ### `input_type: InputType` *(read/write)* The input type for the current camera. ### `serial_number: int` *(read/write)* The serial number of the used ZED camera. ### `pose: Transform` *(read/write)* The WORLD Pose of the camera for Fusion in the unit and coordinate system defined by the user in the InitFusionParameters. ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # FusionMetrics Holds the metrics of the fusion process. ## Properties ### `camera_individual_stats: dict` *(read/write)* Sender metrics. ### `mean_camera_fused: float` *(read/write)* Mean number of camera that provides data during the past second. ### `mean_stdev_between_camera: float` *(read/write)* Standard deviation of the data timestamp fused, the lower the better. ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `reset(self) -> None` Reset the current metrics. --- # GNSSCalibrationParameters Holds the options used for calibrating GNSS / VIO. ## Properties ### `gnss_antenna_position: npt.NDArray[float]` *(read/write)* Define a transform between the GNSS antenna and the camera system for the VIO / GNSS calibration. Default value is [0,0,0], this position can be refined by the calibration if enabled # ### `enable_rolling_calibration: bool` *(read/write)* If this parameter is set to true, the fusion algorithm will used a rough VIO / GNSS calibration at first and then refine it. This allow you to quickly get a fused position. Default: True # ### `gnss_vio_reinit_threshold: float` *(read/write)* This parameter determines the threshold for GNSS/VIO reinitialization. If the fused position deviates beyond out of the region defined by the product of the GNSS covariance and the gnss_vio_reinit_threshold, a reinitialization will be triggered. Default: 5 # ### `target_translation_uncertainty: float` *(read/write)* This parameter defines the target translation uncertainty at which the calibration process between GNSS and VIO concludes. Default: 10e-2 (10 centimeters) # ### `enable_reinitialization: bool` *(read/write)* This parameter determines whether reinitialization should be performed between GNSS and VIO fusion when a significant disparity is detected between GNSS data and the current fusion data. It becomes particularly crucial during prolonged GNSS signal loss scenarios. Default: True # ### `target_yaw_uncertainty: float` *(read/write)* This parameter defines the target yaw uncertainty at which the calibration process between GNSS and VIO concludes. The unit of this parameter is in radian. Default: 0.1 radians # ### `enable_translation_uncertainty_target: bool` *(read/write)* When this parameter is enabled (set to true), the calibration process between GNSS and VIO accounts for the uncertainty in the determined translation, thereby facilitating the calibration termination. The maximum allowable uncertainty is controlled by the 'target_translation_uncertainty' parameter. Default: False # ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # GNSSData Class containing GNSS data to be used for positional tracking as prior. ## Properties ### `gnss_mode: GNSS_MODE` *(read/write)* Represents the current mode of GNSS. ### `ts: Timestamp` *(read/write)* Timestamp of the GNSS position (must be aligned with the camera time reference). ### `gnss_status: GNSS_STATUS` *(read/write)* Represents the current status of GNSS. ### `longitude_std: float` *(read/write)* Longitude standard deviation. ### `position_covariances: list[float]` *(read/write)* Covariance of the position in meter (must be expressed in the ENU coordinate system). For eph, epv GNSS sensors, set it as follow: ```{eph*eph, 0, 0, 0, eph*eph, 0, 0, 0, epv*epv}```. ### `altitude_std: float` *(read/write)* Altitude standard deviation ### `latitude_std: float` *(read/write)* Latitude standard deviation. ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `get_coordinates(self, in_radian=True) -> tuple[float, float, float]` Get the coordinates of the sl.GNSSData. The sl.LatLng coordinates could be expressed in degrees or radians. :param latitude: Latitude coordinate. :param longitude: Longitude coordinate. :param altitude: Altitude coordinate. :param is_radian: Should the output be expressed in radians or degrees. ### `set_coordinates(self, latitude, longitude, altitude, in_radian=True) -> None` Set the sl.LatLng coordinates of sl.GNSSData. The sl.LatLng coordinates could be expressed in degrees or radians. :param latitude: Latitude coordinate. :param longitude: Longitude coordinate. :param altitude: Altitude coordinate. :param is_radian: Are the inputs expressed in radians or in degrees. --- # GeoConverter Purely static class for Geo functions. ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `ecef2latlng(input: ECEF) -> LatLng` Convert ECEF coordinates to Lat/Long coordinates. ### `ecef2utm(input: ECEF) -> UTM` Convert ECEF coordinates to UTM coordinates. ### `latlng2ecef(input: LatLng) -> ECEF` Convert Lat/Long coordinates to ECEF coordinates. ### `latlng2utm(input: LatLng) -> UTM` Convert Lat/Long coordinates to UTM coordinates. ### `utm2ecef(input: UTM) -> ECEF` Convert UTM coordinates to ECEF coordinates. ### `utm2latlng(input: UTM) -> LatLng` Convert UTM coordinates to Lat/Long coordinates. --- # GeoPose Holds Geo reference position. Holds geographic reference position information. This class represents a geographic pose, including position, orientation, and accuracy information. It is used for storing and manipulating geographic data, such as latitude, longitude, altitude, pose matrices, covariances, and timestamps. The pose data is defined in the East-North-Up (ENU) reference frame. The ENU frame is a local Cartesian coordinate system commonly used in geodetic applications. In this frame, the X-axis points towards the East, the Y-axis points towards the North, and the Z-axis points upwards. ## Properties ### `timestamp: Timestamp` *(read/write)* The timestamp associated with the GeoPose. ### `horizontal_accuracy: double` *(read/write)* The horizontal accuracy of the pose in meters. ### `pose_covariance: npt.NDArray[float]` *(read/write)* The pose covariance matrix in ENU. ### `heading: double` *(read/write)* The heading (orientation) of the pose in radians (rad). It indicates the direction in which the object or observer is facing, with 0 degrees corresponding to North and increasing in a counter-clockwise direction. ### `latlng_coordinates: LatLng` *(read/write)* The latitude, longitude, and altitude coordinates of the pose. ### `vertical_accuracy: double` *(read/write)* The vertical accuracy of the pose in meters. ### `pose_data: Transform` *(read/write)* The 4x4 matrix defining the pose in the East-North-Up (ENU) coordinate system. ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # HealthStatus Structure containing the self diagnostic results of the image/depth That information can be retrieved by sl::Camera::get_health_status(), and enabled by sl::InitParameters::enable_image_validity_check The default value of sl::InitParameters::enable_image_validity_check is enabled using the fastest setting, the integer given can be increased to include more advanced and heavier processing to detect issues (up to 3). ## Properties ### `low_lighting: bool` *(read/write)* This status indicates low light scene. As the camera are passive sensors working in the visible range, they requires some external light to operate. This status warns if the lighting condition become suboptimal and worst. This is based on the scene illuminance in LUX for the ZED X cameras series (available with VIDEO_SETTINGS::SCENE_ILLUMINANCE) For other camera models or when using SVO files, this is based on computer vision processing from the image characteristics. ### `low_motion_sensors_reliability: bool` *(read/write)* This status indicates motion sensors data reliability issue. This indicates the IMU is providing low quality data. Possible underlying can be regarding the data stream like corrupted data, timestamp inconsistency, resonance frequencies, saturated sensors / very high acceleration or rotation, shocks ### `low_image_quality: bool` *(read/write)* This status indicates poor image quality It can indicates camera issue, like incorrect manual video settings, damaged hardware, corrupted video stream from the camera, dirt or other partial or total occlusion, stuck ISP (black/white/green/purple images, incorrect exposure, etc), blurry images It also includes widely different left and right images which leads to unavailable depth information In case of very low light this will be reported by this status and the dedicated HealthStatus::low_lighting **Note:** : Frame tearing is currently not detected. Advanced blur detection requires heavier processing and is enabled only when setting Initparameters::enable_image_validity_check to 3 and above ### `low_depth_reliability: bool` *(read/write)* This status indicates low depth map reliability If the image are unreliable or if the scene condition are very challenging this status report a warning. This is using the depth confidence and general depth distribution. Typically due to obstructed eye (included very close object, strong occlusions) or degraded condition like heavy fog/water on the optics ### `enabled: bool` *(read/write)* Indicates if the Health check is enabled ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # IMUData Class containing data from the IMU sensor. ## Properties ### `timestamp: Timestamp` *(read/write)* Data acquisition timestamp. ### `is_available: bool` *(read/write)* Whether the IMU sensor is available in your camera. ### `effective_rate: float` *(read/write)* Realtime data acquisition rate in hertz (Hz). ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `get_angular_velocity_uncalibrated(self, angular_velocity_uncalibrated=[0, 0, 0]) -> list[float]` Gets the angular velocity vector (3x1) of the gyroscope in deg/s (uncorrected from the IMU calibration). :param angular_velocity_uncalibrated: List to be returned. It creates one by default. :return: List fill with the raw angular velocity vector. **Note:** The value is the exact raw values from the IMU. **Note:** Not available in SVO or STREAM mode. ### `get_angular_velocity(self, angular_velocity=[0, 0, 0]) -> list[float]` Gets the angular velocity vector (3x1) of the gyroscope in deg/s. The value is corrected from bias, scale and misalignment. :param angular_velocity: List to be returned. It creates one by default. :return: List fill with the angular velocity vector. **Note:** The value can be directly ingested in an IMU fusion algorithm to extract a quaternion. **Note:** Not available in SVO or STREAM mode. ### `get_linear_acceleration(self, linear_acceleration=[0, 0, 0]) -> list[float]` Gets the linear acceleration vector (3x1) of the gyroscope in m/s². The value is corrected from bias, scale and misalignment. :param linear_acceleration: List to be returned. It creates one by default. :return: List fill with the linear acceleration vector. **Note:** The value can be directly ingested in an IMU fusion algorithm to extract a quaternion. **Note:** Not available in SVO or STREAM mode. ### `get_linear_acceleration_uncalibrated(self, linear_acceleration_uncalibrated=[0, 0, 0]) -> list[float]` Gets the linear acceleration vector (3x1) of the gyroscope in m/s² (uncorrected from the IMU calibration). The value is corrected from bias, scale and misalignment. :param linear_acceleration_uncalibrated: List to be returned. It creates one by default. :return: List fill with the raw linear acceleration vector. **Note:** The value is the exact raw values from the IMU. **Note:** Not available in SVO or STREAM mode. ### `get_angular_velocity_covariance(self, angular_velocity_covariance=None) -> Matrix3f` Gets the covariance matrix of the angular velocity of the gyroscope in deg/s (get_angular_velocity()). :param angular_velocity_covariance: sl.Matrix3f to be returned. It creates one by default. :return: sl.Matrix3f filled with the covariance matrix of the angular velocity. **Note:** Not available in SVO or STREAM mode. ### `get_linear_acceleration_covariance(self, linear_acceleration_covariance=None) -> Matrix3f` Gets the covariance matrix of the linear acceleration of the gyroscope in deg/s (get_angular_velocity()). :param linear_acceleration_covariance: sl.Matrix3f to be returned. It creates one by default. :return: sl.Matrix3f filled with the covariance matrix of the linear acceleration. **Note:** Not available in SVO or STREAM mode. ### `get_pose_covariance(self, pose_covariance=None) -> Matrix3f` Covariance matrix of the IMU pose (get_pose()). :param pose_covariance: sl.Matrix3f to be returned. It creates one by default. :return: sl.Matrix3f filled with the covariance matrix. ### `get_pose(self, pose=None) -> Transform` IMU pose (IMU 6-DoF fusion). :param pose: sl.Transform() to be returned. It creates one by default. :return: sl.Transform filled with the IMU pose. --- # InitFusionParameters Holds the options used to initialize the Fusion object. ## Properties ### `synchronization_parameters: SynchronizationParameter` *(read/write)* Specifies the parameters used for data synchronization during fusion. The SynchronizationParameter struct encapsulates the synchronization parameters that control the data fusion process. ### `maximum_working_resolution: Resolution` *(read/write)* Sets the maximum resolution for all Fusion outputs, such as images and measures. The default value is (-1, -1), which allows the Fusion to automatically select the optimal resolution for the best quality/runtime ratio. - For images, the output resolution can be up to the native resolution of the camera. - For measures involving depth, the output resolution can be up to the maximum working resolution. Setting this parameter to (-1, -1) will ensure the best balance between quality and performance for depth measures. ### `coordinate_system: COORDINATE_SYSTEM` *(read/write)* Positional tracking, point clouds and many other features require a given COORDINATE_SYSTEM to be used as reference. This parameter allows you to select the COORDINATE_SYSTEM used by the Camera to return its measures. This defines the order and the direction of the axis of the coordinate system. Default : COORDINATE_SYSTEM "COORDINATE_SYSTEM::IMAGE" ### `sdk_gpu_id: int` *(read/write)* NVIDIA graphics card id to use. By default the SDK will use the most powerful NVIDIA graphics card found. However, when running several applications, or using several cameras at the same time, splitting the load over available GPUs can be useful. This parameter allows you to select the GPU used by the sl.Camera using an ID from 0 to n-1 GPUs in your PC. Default: -1 **Note:** A non-positive value will search for all CUDA capable devices and select the most powerful. ### `verbose: bool` *(read/write)* Enable the verbosity mode of the SDK. ### `timeout_period_number: int` *(read/write)* If specified change the number of period necessary for a source to go in timeout without data. For example, if you set this to 5 then, if any source do not receive data during 5 period, these sources will go to timeout and will be ignored. ### `coordinate_units: UNIT` *(read/write)* This parameter allows you to select the unit to be used for all metric values of the SDK (depth, point cloud, tracking, mesh, and others). Default : UNIT "UNIT::MILLIMETER" ### `output_performance_metrics: bool` *(read/write)* It allows users to extract some stats of the Fusion API like drop frame of each camera, latency, etc... ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # InitLidarParameters Structure containing the options used to initialize the Lidar object. ## Properties ### `auto_recovery_on_config_change: bool` *(read/write)* Enable automatic recovery when sensor configuration changes externally. When enabled, SDK detects config changes and automatically reconnects. Default: True ### `multicast_mode: LIDAR_MULTICAST_MODE` *(read/write)* Multicast mode for multi-client data sharing. OFF: force unicast, AUTO: smart detection, ON: force multicast. Default: AUTO ### `sdk_verbose: int` *(read/write)* Enable the Lidar SDK verbose mode. This parameter allows you to enable the verbosity of the Lidar SDK to get a variety of runtime information in the console. When developing an application, enabling verbose (``sdk_verbose >= 1``) mode can help you understand the current Lidar SDK behavior. However, this might not be desirable in a shipped version. Default: 1 (verbose messages enabled) **Note:** The verbose messages can also be exported into a log file. **Note:** See sdk_verbose_log_file for more. ### `sdk_verbose_log_file: str` *(read/write)* File path to store the Lidar SDK logs (if sdk_verbose is enabled). The file will be created if it does not exist. Default: "" (logs are printed to console only) ### `svo_real_time_mode: bool` *(read/write)* Defines if the Lidar returns frames in real-time mode during OSF playback. ### `depth_maximum_distance: float` *(read/write)* Maximum distance for data. ### `coordinate_system: COORDINATE_SYSTEM` *(read/write)* Coordinate system for spatial data. ### `input: InputType` *(read/write)* Input type (stream, SVO file, etc.). ### `coordinate_units: UNIT` *(read/write)* Unit of spatial data. ### `multicast_group: str` *(read/write)* Multicast group IP address (range 239.0.0.0 - 239.255.255.255). If empty and multicast_mode is ON, auto-selects 239.201.201.201. Default: "" (empty) ### `depth_minimum_distance: float` *(read/write)* Minimum distance for data. ### `mode: LIDAR_MODE` *(read/write)* Lidar mode (resolution and frequency). ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `__init__(self, mode=LIDAR_MODE.AUTO, depth_minimum_distance=0.0, depth_maximum_distance=0.0, coordinate_units=UNIT.METER, coordinate_system=COORDINATE_SYSTEM.IMAGE, svo_real_time_mode=False, auto_recovery_on_config_change=True, multicast_mode=LIDAR_MULTICAST_MODE.AUTO, multicast_group='', sdk_verbose=1, sdk_verbose_log_file='') -> None` Default constructor. ### `set_from_stream(self, ip, port=0) -> None` Set input from stream IP address. --- # InitParametersOne Class containing the options used to initialize the sl.CameraOne object. This class allows you to select multiple parameters for the sl.Camera such as the selected camera, resolution, depth mode, coordinate system, and units of measurement. Once filled with the desired options, it should be passed to the sl.Camera.open() method. import pyzed.sl as sl def main() : zed = sl.CameraOne() # Create a ZED camera object init_params = sl.InitParametersOne() # Set initial parameters init_params.sdk_verbose = 0 # Disable verbose mode # Use the camera in LIVE mode init_params.camera_resolution = sl.RESOLUTION.HD1080 # Use HD1080 video mode init_params.camera_fps = 30 # Set fps at 30 # Or use the camera in SVO (offline) mode #init_params.set_from_svo_file("xxxx.svo") # Or use the camera in STREAM mode #init_params.set_from_stream("192.168.1.12", 30000) # Other parameters are left to their default values # Open the camera err = zed.open(init_params) if err != sl.ERROR_CODE.SUCCESS: exit(-1) # Close the camera zed.close() return 0 if __name__ == "__main__" : main() With its default values, it opens the camera in live mode at sl.RESOLUTION.HD720 You can customize it to fit your application. **Note:** The parameters can also be saved and reloaded using its save() and load() methods. ## Properties ### `sdk_verbose: int` *(read/write)* Enable the ZED SDK verbose mode. This parameter allows you to enable the verbosity of the ZED SDK to get a variety of runtime information in the console. When developing an application, enabling verbose (``sdk_verbose >= 1``) mode can help you understand the current ZED SDK behavior. However, this might not be desirable in a shipped version. Default: 1 (verbose messages enabled) **Note:** The verbose messages can also be exported into a log file. **Note:** See sdk_verbose_log_file for more. ### `sdk_verbose_log_file: str` *(read/write)* File path to store the ZED SDK logs (if sdk_verbose is enabled). The file will be created if it does not exist. Default: "" **Note:** Setting this parameter to any value will redirect all standard output print calls of the entire program. **Note:** This means that your own standard output print calls will be redirected to the log file. **Warning:** The log file won't be cleared after successive executions of the application. **Warning:** This means that it can grow indefinitely if not cleared. ### `svo_real_time_mode: bool` *(read/write)* Defines if sl.Camera object return the frame in real time mode. When playing back an SVO file, each call to sl.Camera.grab() will extract a new frame and use it. However, it ignores the real capture rate of the images saved in the SVO file. Enabling this parameter will bring the SDK closer to a real simulation when playing back a file by using the images' timestamps. Default: False **Note:** sl.Camera.grab() will return an error when trying to play too fast, and frames will be dropped when playing too slowly. ### `async_grab_camera_recovery: bool` *(read/write)* Define the behavior of the automatic camera recovery during sl.Camera.grab() method call. When async is enabled and there's an issue with the communication with the sl.Camera object, sl.Camera.grab() will exit after a short period and return the sl.ERROR_CODE.CAMERA_REBOOTING warning. The recovery will run in the background until the correct communication is restored. When async_grab_camera_recovery is false, the sl.Camera.grab() method is blocking and will return only once the camera communication is restored or the timeout is reached. Default: False ### `camera_resolution: RESOLUTION` *(read/write)* Desired camera resolution. **Note:** Small resolutions offer higher framerate and lower computation time. **Note:** In most situations, sl.RESOLUTION.HD720 at 60 FPS is the best balance between image quality and framerate. Default: sl.RESOLUTION.AUTO * Resolves to sl.RESOLUTION.HD1200 for ZED X/X Mini * Resolves to sl.RESOLUTION.HD720 for other cameras **Note:** Available resolutions are listed here: sl.RESOLUTION. ### `coordinate_system: COORDINATE_SYSTEM` *(read/write)* sl.COORDINATE_SYSTEM to be used as reference for positional tracking, mesh, point clouds, etc. This parameter allows you to select the sl.COORDINATE_SYSTEM used by the sl.Camera object to return its measures. This defines the order and the direction of the axis of the coordinate system. Default: sl.COORDINATE_SYSTEM.IMAGE ### `optional_settings_path: str` *(read/write)* Optional path where the ZED SDK has to search for the settings file (SN.conf file). This file contains the calibration information of the camera. Default: "" **Note:** The settings file will be searched in the default directory: * **Linux**: /usr/local/zed/settings/ * **Windows**: C:/ProgramData/stereolabs/settings **Note:** If a path is specified and no file has been found, the ZED SDK will search the settings file in the default directory. **Note:** An automatic download of the settings file (through **ZED Explorer** or the installer) will still download the files on the default path. init_params = sl.InitParametersOne() # Set initial parameters home = "/path/to/home" path = home + "/Documents/settings/" # assuming /path/to/home/Documents/settings/SNXXXX.conf exists. Otherwise, it will be searched in /usr/local/zed/settings/ init_params.optional_settings_path = path ### `enable_hdr: bool` *(read/write)* Activates HDR support for the current resolution/mode. Only active if the camera supports HDR for this resolution Default: False ### `input: InputType` *(read/write)* The SDK can handle different input types: - Select a camera by its ID (/dev/videoX on Linux, and 0 to N cameras connected on Windows) - Select a camera by its serial number - Open a recorded sequence in the SVO file format - Open a streaming camera from its IP address and port This parameter allows you to select to desired input. It should be used like this: init_params = sl.InitParametersOne() # Set initial parameters init_params.sdk_verbose = 1 # Enable verbose mode input_t = sl.InputType() input_t.set_from_camera_id(0) # Selects the camera with ID = 0 init_params.input = input_t init_params.set_from_camera_id(0) # You can also use this init_params = sl.InitParametersOne() # Set initial parameters init_params.sdk_verbose = 1 # Enable verbose mode input_t = sl.InputType() input_t.set_from_serial_number(1010) # Selects the camera with serial number = 101 init_params.input = input_t init_params.set_from_serial_number(1010) # You can also use this init_params = sl.InitParametersOne() # Set initial parameters init_params.sdk_verbose = 1 # Enable verbose mode input_t = sl.InputType() input_t.set_from_svo_file("/path/to/file.svo") # Selects the and SVO file to be read init_params.input = input_t init_params.set_from_svo_file("/path/to/file.svo") # You can also use this init_params = sl.InitParametersOne() # Set initial parameters init_params.sdk_verbose = 1 # Enable verbose mode input_t = sl.InputType() input_t.set_from_stream("192.168.1.42") init_params.input = input_t init_params.set_from_stream("192.168.1.42") # You can also use this Available cameras and their ID/serial can be listed using get_device_list() and get_streaming_device_list() Each Camera will create its own memory (CPU and GPU), therefore the number of ZED used at the same time can be limited by the configuration of your computer. (GPU/CPU memory and capabilities) default : empty See InputType for complementary information. **Warning:** Using the ZED SDK Python API, using init_params.input.set_from_XXX won't work, use init_params.set_from_XXX instead ### `camera_fps: int` *(read/write)* Requested camera frame rate. If set to 0, the highest FPS of the specified camera_resolution will be used. Default: 0 See sl.RESOLUTION for a list of supported frame rates. **Note:** If the requested camera_fps is unsupported, the closest available FPS will be used. ### `svo_decryption_key: str` *(read/write)* Optional passphrase or key to decrypt an encrypted SVO file. Required when opening an SVO file that was recorded with RecordingParameters.encryption_key. The value is interpreted as a file path (raw 32-byte or hex key file), a 64-char hex string (raw AES-256 key), or a passphrase (PBKDF2-SHA256 derived). Default: "" (no decryption) **Note:** If the SVO file is encrypted and this field is empty or contains a wrong key, sl.CameraOne.open() will return sl.ERROR_CODE.INVALID_SVO_FILE. ### `coordinate_units: UNIT` *(read/write)* Unit of spatial data (depth, point cloud, tracking, mesh, etc.) for retrieval. Default: sl.UNIT.MILLIMETER ### `sdk_gpu_id: int` *(read/write)* NVIDIA graphics card id to use. By default the SDK will use the most powerful NVIDIA graphics card found. However, when running several applications, or using several cameras at the same time, splitting the load over available GPUs can be useful. This parameter allows you to select the GPU used by the sl.CameraOne using an ID from 0 to n-1 GPUs in your PC. Default: -1 **Note:** A non-positive value will search for all CUDA capable devices and select the most powerful. ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `set_from_camera_id(self, cam_id, bus_type: BUS_TYPE=BUS_TYPE.AUTO) -> None` Defines the input source with a camera id to initialize and open an sl.CameraOne object from. :param id: Id of the desired camera to open. :param bus_type: sl.BUS_TYPE of the desired camera to open. ### `set_from_serial_number(self, serial_number) -> None` Defines the input source with a serial number to initialize and open an sl.CameraOne object from. For ZED/ZEDOne cameras (numeric serial numbers), pass an int or a numeric string. For Lidar sensors (string-based serial numbers like "991937000508"), pass a string. :param serial_number: Serial number of the desired camera/sensor to open (int or str). ### `set_from_svo_file(self, svo_input_filename) -> None` Defines the input source with an SVO file to initialize and open an sl.CameraOne object from. :param svo_input_filename: Path to the desired SVO file to open. ### `set_from_stream(self, sender_ip, port=30000) -> None` Defines the input source from a stream to initialize and open an sl.CameraOne object from. :param sender_ip: IP address of the streaming sender. :param port: Port on which to listen. Default: 30000 ### `set_from_gmsl_port(self, gmsl_port=-1) -> None` Defines the input source as the camera with the specified GMSL port. :param gmsl_port: GMSL port number of the camera to open. Default: -1. Any number < 0 will try to open the first available GMSL camera. --- # InitSensorsParameters Structure containing a set of parameters for the Sensors module initialization. ## Properties ### `execution_mode: SENSORS_EXECUTION_MODE` *(read/write)* Execution mode for the Sensors pipeline (EAGER or PIPELINED). In PIPELINED mode, after a one-frame setup phase, worker threads run autonomously. ### `output_performance_metrics: bool` *(read/write)* Extract some stats of the Fusion API like drop frame of each camera, latency, etc... ### `coordinate_system: COORDINATE_SYSTEM` *(read/write)* Coordinate system used by the Sensors to return its measures. ### `verbose: int` *(read/write)* Enable the verbosity mode of the SDK. ### `sync_policy: SENSORS_SYNC_POLICY` *(read/write)* Sync policy for temporal alignment across devices in pipelined mode. ### `sync_tolerance: Timestamp` *(read/write)* Maximum timestamp difference (nanoseconds) for temporal sync. Only effective when sync_policy is not NONE. ### `coordinate_units: UNIT` *(read/write)* Unit to be used for all metric values of the SDK. ### `sdk_gpu_id: int` *(read/write)* NVIDIA graphics card to use. ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `__init__(self, coordinate_units=UNIT.MILLIMETER, coordinate_system=COORDINATE_SYSTEM.IMAGE, output_performance_metrics=False, verbose=0, sdk_gpu_id=-1, maximum_working_resolution=Resolution(0, 0), execution_mode=SENSORS_EXECUTION_MODE.EAGER, sync_policy=SENSORS_SYNC_POLICY.NONE, sync_tolerance=None) -> None` Default constructor. :param coordinate_units: Chosen coordinate_units :param coordinate_system: Chosen coordinate_system :param output_performance_metrics: Activates output_performance_metrics :param verbose: Sets verbose :param sdk_gpu_id: Chosen sdk_gpu_id :param maximum_working_resolution: Sets maximum_working_resolution :param execution_mode: Execution mode (EAGER or PIPELINED). :param sync_policy: Sync policy for temporal alignment across devices. :param sync_tolerance: Maximum timestamp difference for sync (in nanoseconds as a Timestamp). --- # InputType Class defining the input type used in the ZED SDK. It can be used to select a specific camera with an id or serial number, or from a SVO file. ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `set_from_camera_id(self, cam_id, bus_type: BUS_TYPE=BUS_TYPE.AUTO) -> None` Set the input as the camera with specified id. **Note:** The id is not related to the serial number of the camera. The id is assigned by the OS depending on the order the cameras are plugged. **Warning:** Using id is not recommended if you have multiple cameras plugged in the system, prefer using the serial number instead. :param id: Id of the camera to open. The default, -1, will open the first available camera. A number >= 0 will try to open the camera with the corresponding id. :param bus_type: Whether the camera is a USB or a GMSL camera. ### `set_from_serial_number(self, serial_number) -> None` Set the input as the camera with specified serial number. For ZED/ZEDOne cameras (numeric serial numbers), pass an int or a numeric string. For Lidar sensors (string-based serial numbers like "991937000508"), pass a string. :param serial_number: Serial number of the camera/sensor to open (int or str). ### `set_from_serial_port(self, gmsl_port=-1) -> None` Set the input as the camera with specified GMSL port. :param gmsl_port: GMSL port number of the camera to open. Default: -1. Any number < 0 will try to open the first available GMSL camera. ### `set_virtual_stereo_from_camera_id(self, id_left, id_right, virtual_serial_number) -> bool` Set the input as a virtual stereo camera from two cameras with specified ids. :param id_left: Id of the left camera. :param id_right: Id of the right camera. :param virtual_serial_number: Serial number of the virtual stereo camera. **Note:** : The virtual serial number must fall within an interval that reflects the Product ID range. This is necessary to avoid, for instance, downloading calibration data from an unrelated product. The valid range is 110000000 to 119999999. A support function can be used, based on the ZED One serial number, to compute a valid virtual serial number: generate_virtual_stereo_serial_number :return: False if there's no error and the camera was successfully created, otherwise True. ### `set_virtual_stereo_from_serial_numbers(self, camera_left_serial_number, camera_right_serial_number, virtual_serial_number) -> bool` Set the input as a virtual stereo camera from two cameras with specified serial numbers. :param camera_left_serial_number: Serial number of the left camera. :param camera_right_serial_number: Serial number of the right camera. :param virtual_serial_number: Serial number of the virtual stereo camera. **Note:** : The virtual serial number must fall within an interval that reflects the Product ID range. This is necessary to avoid, for instance, downloading calibration data from an unrelated product. The valid range is 110000000 to 119999999. A support function can be used, based on the ZED One serial number, to compute a valid virtual serial number: generate_virtual_stereo_serial_number :return: False if there's no error and the camera was successfully created, otherwise True. ### `set_from_svo_file(self, svo_input_filename) -> None` Set the input as the svo specified with the filename :param svo_input_filename: The path to the desired SVO file ### `set_from_stream(self, sender_ip, port=30000) -> None` Set the input to stream with the specified ip and port :param sender_ip: The IP address of the streaming sender :param port: The port on which to listen. Default: 30000 **Note:** The protocol used for the streaming module is based on RTP/RTCP. **Warning:** Port must be even number, since the port+1 is used for control data. ### `get_type(self) -> TYPE_OF_INPUT_TYPE` Returns the current type of the input type. ### `get_configuration(self) -> str` Returns the current input configuration as a string e.g: SVO name, serial number, streaming ip, etc. ### `is_init(self) -> bool` Check whether the input is set. --- # KeyFrame Represents a keyframe in the tracking system. ## Properties ### `timestamp: Timestamp` *(read/write)* Timestamp when the keyframe was captured. ### `pose: Transform` *(read/write)* Position and orientation of the keyframe. ### `is_loaded: bool` *(read/write)* Boolean indicating if the keyframe come from a loaded area file. ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # Landmark Represents a 3d landmark. ## Properties ### `id: int` *(read/write)* The ID of the landmark. ### `position: list[float]` *(read/write)* The position of the landmark. ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # Landmark2D Represents the projection of a 3d landmark in the image. ## Properties ### `position: npt.NDArray` *(read/write)* The position of the landmark in the image. ### `dynamic_confidence: float` *(read-only)* Confidence score indicating the likelihood that the landmark is associated with a dynamic object. The value ranges from 0 to 1, where a smaller value indicates greater confidence that the landmark is owned by a dynamic object. The value is -1 if the dynamic confidence is not computed. ### `id: int` *(read-only)* Unique identifier of the corresponding landmark. ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # LatLng Represents a world position in LatLng format. ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `get_latitude(self, in_radian: bool=True) -> None` Get the latitude coordinate :param in_radian: Is the output should be in radian or degree. :return: Latitude in radian or in degree depending in_radian parameter. ### `get_longitude(self, in_radian=True) -> None` Get the longitude coordinate :param in_radian: Is the output should be in radian or degree. :return: Longitude in radian or in degree depending in_radian parameter. ### `get_altitude(self) -> None` Get the altitude coordinate :return: Altitude coordinate in meters. ### `get_coordinates(self, in_radian=True) -> None` Get the coordinates in radians (default) or in degrees. :param latitude: Latitude coordinate. :param longitude: Longitude coordinate. :param altitude: Altitude coordinate. :param in_radian: Should the output be expressed in radians or degrees. ### `set_coordinates(self, latitude, longitude, altitude, in_radian=True) -> None` Set the coordinates in radians (default) or in degrees. :param latitude: Latitude coordinate. :param longitude: Longitude coordinate. :param altitude: Altitude coordinate. \@param in_radian: Is input are in radians or in degrees. --- # Lidar Class for managing a LiDAR device. ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `get_device_list() -> list[LidarDeviceProperties]` Returns a list of available LiDAR devices. ### `get_streaming_device_list() -> list[LidarDeviceProperties]` Returns a list of streaming LiDAR devices. ### `open(self, params) -> ERROR_CODE` Opens the LiDAR. ### `is_opened(self) -> bool` Checks if the LiDAR is opened. ### `get_init_parameters(self) -> InitLidarParameters` Returns the initialization parameters used to open the LiDAR. ### `get_lidar_information(self) -> LidarInformation` Returns information about the Lidar sensor. ### `read(self) -> ERROR_CODE` Reads the latest data from the LiDAR sensor. ### `grab(self) -> ERROR_CODE` Grabs and processes a new frame of data. ### `retrieve_measure(self, py_mat, measure=LIDAR_MEASURE.XYZ, resolution=None, mem_type=MEM.CPU, color_map=VIEW_COLOR_MAP.AUTO) -> ERROR_CODE` Retrieves a measure from the LiDAR. :param py_mat: The Mat to store the measure. :param measure: The type of measure to retrieve. :param resolution: The desired resolution. :param mem_type: The memory type (CPU/GPU). :param color_map: The colormap for visualization. ### `retrieve_view(self, py_mat, view=LIDAR_VIEW.DEPTH, resolution=None, color_map=VIEW_COLOR_MAP.AUTO) -> ERROR_CODE` Retrieves a view image from the LiDAR. :param py_mat: The Mat to store the view. :param view: The type of view to retrieve. :param resolution: The desired resolution. :param color_map: The colormap for visualization. ### `get_timestamp(self, reference_time=TIME_REFERENCE.IMAGE) -> Timestamp` Returns the current timestamp. ### `get_current_fps(self) -> float` Returns the current framerate. ### `get_sensors_data(self, data, reference_time=TIME_REFERENCE.IMAGE) -> ERROR_CODE` Returns the sensors data (IMU, etc.) from the LiDAR. ### `enable_positional_tracking(self, params=None) -> ERROR_CODE` Enables positional tracking for the LiDAR. ### `disable_positional_tracking(self) -> None` Disables positional tracking. ### `get_position(self, py_pose, reference_frame=REFERENCE_FRAME.WORLD) -> POSITIONAL_TRACKING_STATE` Returns the current position of the LiDAR. ### `enable_recording(self, params) -> ERROR_CODE` Enables recording of LiDAR data. ### `disable_recording(self) -> None` Disables recording. ### `get_svo_position(self) -> int` Returns the current SVO playback position. ### `set_svo_position(self, position: int) -> ERROR_CODE` Sets the SVO playback position. ### `get_svo_number_of_frames(self) -> int` Returns the total number of frames in the SVO. ### `get_svo_position_at_timestamp(self, timestamp) -> int` Returns the SVO position at a specific timestamp. ### `set_timestamp_base_offset(self, offset_ns: int) -> None` Sets the timestamp base offset. ### `get_timestamp_base_offset(self) -> int` Returns the timestamp base offset. ### `pause_svo_reading(self, pause: bool) -> None` Pauses or resumes SVO reading. ### `close(self) -> None` Closes the LiDAR and releases resources. --- # LidarCalibration Structure containing beam geometry calibration data for raw data processing. ## Properties ### `pixel_shift_by_row: list` *(read-only)* Per-row pixel shift for destaggering raw data. ### `lidar_origin_to_beam_origin_mm: float` *(read-only)* Distance from lidar origin to beam origin in millimeters. ### `beam_to_lidar_transform: Matrix4f` *(read-only)* 4x4 transform from beam frame to lidar frame. ### `beam_altitude_angles: list` *(read-only)* Vertical angle of each beam in degrees. ### `beam_azimuth_angles: list` *(read-only)* Horizontal angle offset of each beam in degrees. ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # LidarDeviceProperties Structure containing information about a connected LiDAR device. ## Properties ### `imu_port: int` *(read-only)* Device IMU port number. ### `port: int` *(read-only)* Device port number. ### `name: str` *(read-only)* Device name (e.g. "OS1-128"). ### `ip_address: str` *(read-only)* Device IP address (specific to Ouster). ### `sensor_state: SENSOR_STATE` *(read-only)* Sensor state (AVAILABLE, etc.). ### `lidar_information: LidarInformation` *(read-only)* Device information (serial number, firmware, configuration, etc.). ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # LidarInformation Structure containing information about the Lidar device. ## Properties ### `status: str` *(read-only)* Status of the Lidar sensor. ### `firmware_version: str` *(read-only)* Firmware version of the Lidar sensor. ### `sensor_configuration: LidarSensorConfiguration` *(read-only)* Sensor configuration (resolution, fps, calibration, etc.). ### `product_line: str` *(read-only)* Product line of the Lidar sensor. ### `product_part_number: str` *(read-only)* Product part number of the Lidar sensor. ### `image_rev: str` *(read-only)* Image revision of the Lidar sensor. ### `serial_number: str` *(read-only)* Serial number of the Lidar sensor. ### `build_date: str` *(read-only)* Build date of the Lidar sensor. ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # LidarSensorConfiguration Structure containing runtime configuration of the Lidar sensor. ## Properties ### `vertical_fov: float` *(read-only)* Vertical field of view in degrees. ### `vertical_resolution: int` *(read-only)* Vertical resolution (number of channels/beams). ### `calibration: LidarCalibration` *(read-only)* Beam geometry calibration for raw data processing. ### `imu_to_lidar_transform: Transform` *(read-only)* Transform from IMU frame to Lidar frame. ### `fps: float` *(read-only)* Frame rate in Hz. ### `horizontal_fov: float` *(read-only)* Horizontal field of view in degrees. ### `horizontal_resolution: int` *(read-only)* Horizontal resolution (number of columns per frame). ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # MagnetometerData Class containing data from the magnetometer sensor. ## Properties ### `magnetic_heading: float` *(read/write)* Camera heading in degrees relative to the magnetic North Pole. **Note:** The magnetic North Pole has an offset with respect to the geographic North Pole, depending on the geographic position of the camera. **Note:** To get a correct magnetic heading, the magnetometer sensor must be calibrated using **ZED **Sensor **Viewer tool. ### `is_available: bool` *(read/write)* Whether the magnetometer sensor is available in your camera. ### `effective_rate: float` *(read/write)* Realtime data acquisition rate in hertz (Hz). ### `timestamp: Timestamp` *(read/write)* Data acquisition timestamp. ### `magnetic_heading_accuracy: float` *(read/write)* Accuracy of magnetic_heading measure in the range [0.0, 1.0]. **Note:** A negative value means that the magnetometer must be calibrated using **ZED **Sensor **Viewer tool. ### `magnetic_heading_state: HEADING_STATE` *(read/write)* State of magnetic_heading. ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `get_magnetic_field_uncalibrated(self) -> npt.NDArray[float]` Gets the uncalibrated magnetic field local vector in microtesla (μT). **Note:** The magnetometer raw values are affected by soft and hard iron interferences. **Note:** The sensor must be calibrated by placing the camera in the working environment and using **ZED **Sensor **Viewer tool. **Note:** Not available in SVO or STREAM mode. ### `get_magnetic_field_calibrated(self) -> npt.NDArray[float]` Gets the magnetic field local vector in microtesla (μT). **Note:** To calibrate the magnetometer sensor, please use **ZED **Sensor **Viewer tool after placing the camera in the final operating environment. --- # Matrix3f Class representing a generic 3*3 matrix. It is defined in a row-major order, it means that, in the value buffer, the entire first row is stored first, followed by the entire second row, and so on. The data value of the matrix can be accessed with the r() method. | r00 r01 r02 | | r10 r11 r12 | | r20 r21 r22 | ## Properties ### `matrix_name: str` *(read/write)* Name of the matrix (optional). ### `nbElem: int` *(read-only)* Number of elements in the matrix (always 9). ### `r: np.numpy[float][float]` *(read/write)* 3*3 numpy array of inner data. ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `_initialize_from_input(self, input_data) -> None` ### `init_matrix(self, matrix) -> None` Copy the values from another sl.Matrix3f. :param matrix: sl.Matrix3f to copy. ### `inverse(self) -> None` Sets the sl.Matrix3f to its inverse. ### `inverse_mat(self, rotation) -> Matrix3f` Returns the inverse of a sl.Matrix3f. :param rotation: sl.Matrix3f to compute the inverse from. :return: The inverse of the sl.Matrix3f given as input. ### `transpose(self) -> None` Sets the sl.Matrix3f to its transpose. ### `transpose_mat(self, rotation) -> Matrix3f` Returns the transpose of a sl.Matrix3f. :param rotation: sl.Matrix3f to compute the transpose from. :return: The transpose of the sl.Matrix3f given as input. ### `set_identity(self) -> Matrix3f` Sets the sl.Matrix3f to identity. :return: itself ### `identity() -> Matrix3f` Creates an identity sl.Matrix3f. :return: A sl.Matrix3f set to identity. ### `set_zeros(self) -> None` Sets the sl.Matrix3f to zero. ### `zeros() -> Matrix3f` Creates a sl.Matrix3f filled with zeros. :return: A sl.Matrix3f filled with zeros. ### `get_infos(self) -> str` Returns the components of the sl.Matrix3f in a string. :return: A string containing the components of the current sl.Matrix3f. --- # Matrix4f Class representing a generic 4*4 matrix. It is defined in a row-major order, it means that, in the value buffer, the entire first row is stored first, followed by the entire second row, and so on. The data value of the matrix can be accessed with the r() method. | r00 r01 r02 tx | | r10 r11 r12 ty | | r20 r21 r22 tz | | m30 m31 m32 m33 | ## Properties ### `matrix_name: str` *(read/write)* Returns the name of the matrix (optional). ### `m: np.numpy[float][float]` *(read/write)* 4*4 numpy array of inner data. ### `nbElem: int` *(read-only)* Number of elements in the matrix (always 16). ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `_initialize_from_input(self, input_data) -> None` ### `init_matrix(self, matrix: Matrix4f) -> None` Copy the values from another sl.Matrix4f. :param matrix: sl.Matrix4f to copy. ### `inverse(self) -> ERROR_CODE` Sets the sl.Matrix4f to its inverse. :return: sl.ERROR_CODE.SUCCESS if the inverse has been computed, sl.ERROR_CODE.FAILURE is not (det = 0). ### `inverse_mat(self, rotation: Matrix4f) -> Matrix4f` Returns the inverse of a sl.Matrix4f. :param rotation: sl.Matrix4f to compute the inverse from. :return: The inverse of the sl.Matrix4f given as input. ### `transpose(self) -> None` Sets the sl.Matrix4f to its transpose. ### `transpose_mat(self, rotation: Matrix4f) -> Matrix4f` Returns the transpose of a sl.Matrix4f. :param rotation: sl.Matrix4f to compute the transpose from. :return: The transpose of the sl.Matrix4f given as input. ### `set_identity(self) -> Matrix4f` Sets the sl.Matrix4f to identity. :return: itself ### `identity() -> None` Creates an identity sl.Matrix4f. :return: A sl.Matrix3f set to identity. ### `set_zeros(self) -> None` Sets the sl.Matrix4f to zero. ### `zeros() -> Matrix4f` Creates a sl.Matrix4f filled with zeros. :return: A sl.Matrix4f filled with zeros. ### `get_infos(self) -> str` Returns the components of the sl.Matrix4f in a string. :return: A string containing the components of the current sl.Matrix4f. ### `set_sub_matrix3f(self, input: Matrix3f, row=0, column=0) -> ERROR_CODE` Sets a sl.Matrix3f inside the sl.Matrix4f. **Note:** Can be used to set the rotation matrix when the sl.Matrix4f is a pose or an isometric matrix. :param input: Sub-matrix to put inside the sl.Matrix4f. :param row: Index of the row to start the 3x3 block. Must be 0 or 1. :param column: Index of the column to start the 3x3 block. Must be 0 or 1. :return: sl.ERROR_CODE.SUCCESS if everything went well, sl.ERROR_CODE.FAILURE otherwise. ### `set_sub_vector3f(self, input0: float, input1: float, input2: float, column=3) -> ERROR_CODE` Sets a 3x1 Vector inside the sl.Matrix4f at the specified column index. **Note:** Can be used to set the translation/position matrix when the sl.Matrix4f is a pose or an isometry. :param input0: First value of the 3x1 Vector to put inside the sl.Matrix4f. :param input1: Second value of the 3x1 Vector to put inside the sl.Matrix4f. :param input2: Third value of the 3x1 Vector to put inside the sl.Matrix4f. :param column: Index of the column to start the 3x3 block. By default, it is the last column (translation for a sl.Pose). :return: sl.ERROR_CODE.SUCCESS if everything went well, sl.ERROR_CODE.FAILURE otherwise. ### `set_sub_vector4f(self, input0: float, input1: float, input2: float, input3: float, column=3) -> ERROR_CODE` Sets a 4x1 Vector inside the sl.Matrix4f at the specified column index. :param input0: First value of the 4x1 Vector to put inside the sl.Matrix4f. :param input1: Second value of the 4x1 Vector to put inside the sl.Matrix4f. :param input2: Third value of the 4x1 Vector to put inside the sl.Matrix4f. :param input3: Fourth value of the 4x1 Vector to put inside the sl.Matrix4f. :param column: Index of the column to start the 3x3 block. By default, it is the last column (translation for a sl.Pose). :return: sl.ERROR_CODE.SUCCESS if everything went well, sl.ERROR_CODE.FAILURE otherwise. --- # Mesh Class representing a mesh and containing the geometric (and optionally texture) data of the scene captured by the spatial mapping module. By default the mesh is defined as a set of chunks. This way we update only the data that has to be updated avoiding a time consuming remapping process every time a small part of the sl.Mesh is updated. ## Properties ### `texture: Mat` *(read-only)* Texture of the sl.Mesh. **Note:** Contains data only if your mesh has textures (by loading it or calling sl.Mesh.apply_texture()). ### `vertices: npt.NDArray[float]` *(read-only)* NumPy array of vertices. Vertices are defined by a 3D point ```[x, y, z]```. ### `chunks: list[Chunk]` *(read-only)* List of chunks constituting the sl.Mesh. ### `normals: npt.NDArray[float]` *(read-only)* NumPy array of normals. Normals are defined by three components ```[nx, ny, nz]```. **Note:** A normal is defined for each vertex. ### `colors: npt.NDArray[int]` *(read-only)* NumPy array of colors. Colors are defined by three components ```[r, g, b]```. **Note:** A color is defined for each vertex. ### `triangles: npt.NDArray[int]` *(read-only)* NumPy array of triangles/faces. Triangle defined as a set of three vertices indexes ```[v1, v2, v3]```. ### `uv: npt.NDArray[float]` *(read-only)* UVs defines the 2D projection of each vertices onto the texture. Values are normalized [0, 1] and start from the bottom left corner of the texture (as requested by OpenGL). In order to display a textured mesh you need to bind the texture and then draw each triangle by picking its uv values. **Note:** Contains data only if your mesh has textures (by loading it or calling sl.Mesh.apply_texture()). ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `filter(self, params=None, update_chunk_only=False) -> bool` Filters the mesh. The resulting mesh is smoothed, small holes are filled, and small blobs of non-connected triangles are deleted. :param params: Filtering parameters. Default: a preset of sl.MeshFilterParameters. :param update_chunk_only: Whether to only update chunks (and not vertices / normals / triangles). Default: False. :return: True if the mesh was successfully filtered, otherwise False. **Note:** The filtering is a costly operation. **Note:** It is not recommended to call it every time you retrieve a mesh but only at the end of your spatial mapping process. ### `apply_texture(self, texture_format=MESH_TEXTURE_FORMAT.RGB) -> bool` Applies a texture to the mesh. By using this method you will get access to uv, and texture. The number of triangles in the mesh may slightly differ before and after calling this method due to missing texture information. There is only one texture for the mesh, the uv of each chunk are expressed for it in its entirety. NumPy arrays of vertices / normals and uv have now the same size. :param texture_format: Number of channels desired for the computed texture. Default: sl.MESH_TEXTURE_FORMAT.RGB. :return: True if the mesh was successfully textured, otherwise False. **Note:** This method can be called as long as you do not start a new spatial mapping process (due to shared memory). **Note:** This method can require a lot of computation time depending on the number of triangles in the mesh. **Note:** It is recommended to call it once at the end of your spatial mapping process. **Warning:** The sl.SpatialMappingParameters.save_texture parameter must be set to True when enabling the spatial mapping to be able to apply the textures. **Warning:** The mesh should be filtered before calling this method since filter() will erase the textures. **Warning:** The texturing is also significantly slower on non-filtered meshes. ### `save(self, filename: str, typeMesh=MESH_FILE_FORMAT.OBJ, id=[]) -> bool` Saves the current sl.Mesh into a file. :param filename: Path of the file to store the mesh in. :param typeMesh: File extension type. Default: sl.MESH_FILE_FORMAT.OBJ. :param id: Set of chunks to be saved. Default: (empty) (all chunks are saved) :return: True if the file was successfully saved, otherwise False. **Note:** Only sl.MESH_FILE_FORMAT.OBJ supports textures data. **Note:** This method operates on the sl.Mesh not on chunks. **Note:** This way you can save different parts of your sl.Mesh by updating it with update_mesh_from_chunklist(). ### `load(self, filename: str, update_mesh=False) -> bool` Loads the mesh from a file. :param filename: Path of the file to load the mesh from. :param update_mesh: Whether to only load data in chunks (and not vertices / normals / triangles). Default: False. :return: True if the mesh was successfully loaded, otherwise False. **Note:** Updating a sl::Mesh is time consuming. Consider using only chunks for better performances. ### `clear(self) -> None` Clears all the data. ### `get_number_of_triangles(self) -> int` Computes the total number of triangles stored in all chunks. :return: The number of triangles stored in all chunks. ### `get_boundaries(self) -> npt.NDArray[int]` Compute the indices of boundary vertices. :return: The indices of boundary vertices. ### `merge_chunks(self, faces_per_chunk: int) -> None` Merges current chunks. This method can be used to merge chunks into bigger sets to improve rendering process. :param faces_per_chunk: Number of faces per chunk. **Note:** This method is useful for Unity, which does not handle chunks with more than 65K vertices. **Warning:** This method should not be called during spatial mapping process since mesh updates will revert this changes. ### `get_gravity_estimate(self) -> npt.NDArray[float]` Estimates the gravity vector. This method looks for a dominant plane in the whole mesh considering that it is the floor (or a horizontal plane). :return: The estimated gravity vector (NumPy array). **Note:** This can be used to find the gravity to create realistic physical interactions. ### `get_visible_list(self, camera_pose: Transform) -> list[int]` Computes the id list of visible chunks from a specific point of view. :param camera_pose: Point of view (given in the same reference as the vertices). :return: The list of id of visible chunks. ### `get_surrounding_list(self, camera_pose: Transform, radius: float) -> list[int]` Computes the id list of chunks close to a specific point of view. :param camera_pose: Point of view (given in the same reference as the vertices). :param radius: Radius determining closeness (given in the same unit as the mesh). :return: The list of id of chunks close to the given point. ### `update_mesh_from_chunklist(self, id=[]) -> None` Updates vertices / normals / triangles / uv from chunk data pointed by the given list of id. :param id: Indices of chunks which will be concatenated. Default: (empty). **Note:** If the given list of id is empty, all chunks will be used to update the current sl.Mesh. --- # MeshFilterParameters Class containing a set of parameters for the mesh filtration functionality. The default constructor sets all parameters to their default settings. **Note:** Parameters can be adjusted by the user. ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `set(self, filter=MESH_FILTER.LOW) -> None` Set the filtering intensity. :param filter: Desired sl.MESH_FILTER. ### `save(self, filename: str) -> bool` Saves the current set of parameters into a file to be reloaded with the load() method. :param filename: Name of the file which will be created to store the parameters. :return: True if the file was successfully saved, otherwise False. **Warning:** For security reasons, the file must not already exist. **Warning:** In case a file already exists, the method will return False and existing file will not be updated. ### `load(self, filename: str) -> bool` Loads a set of parameters from the values contained in a previously save() "saved" file. :param filename: Path to the file from which the parameters will be loaded. :return: True if the file was successfully loaded, otherwise False. --- # ObjectData Class containing data of a detected object such as its bounding_box, label, id and its 3D position. ## Properties ### `unique_object_id: str` *(read/write)* Unique id to help identify and track AI detections. It can be either generated externally, or by using generate_unique_id() or left empty. ### `action_state: OBJECT_ACTION_STATE` *(read/write)* Object action state. ### `position_covariance: npt.NDArray[float]` *(read/write)* Covariance matrix of the 3D position. **Note:** It is represented by its upper triangular matrix value = [p0, p1, p2] [p1, p3, p4] [p2, p4, p5] where pi is ```position_covariance[i]``` ### `sublabel: OBJECT_SUBCLASS` *(read/write)* Object sub-class/sub-category to identify the object type. ### `head_bounding_box_2d: npt.NDArray[int][int]` *(read-only)* 2D bounding box of the head of the object (a person) represented as four 2D points starting at the top left corner and rotation clockwise. **Note:** Expressed in pixels on the original image resolution, ```[0, 0]``` is the top left corner. **Warning:** Not available with sl.OBJECT_DETECTION_MODEL.MULTI_CLASS_BOX_XXX. ### `dimensions: npt.NDArray[float]` *(read/write)* 3D object dimensions: width, height, length. **Note:** It is defined in sl.InitParameters.coordinate_units and expressed in sl.RuntimeParameters.measure3D_reference_frame. ### `confidence: float` *(read/write)* Detection confidence value of the object. From 0 to 100, a low value means the object might not be localized perfectly or the label (sl.OBJECT_CLASS) is uncertain. ### `head_bounding_box: npt.NDArray[float][float]` *(read-only)* 3D bounding box of the head of the object (a person) represented as eight 3D points. **Note:** It is defined in sl.InitParameters.coordinate_units and expressed in sl.RuntimeParameters.measure3D_reference_frame. **Warning:** Not available with sl.OBJECT_DETECTION_MODEL.MULTI_CLASS_BOX_XXX. ### `raw_label: int` *(read/write)* Object raw label. It is forwarded from sl.CustomBoxObjectData when using sl.OBJECT_DETECTION_MODEL.CUSTOM_BOX_OBJECTS. ### `label: OBJECT_CLASS` *(read/write)* Object class/category to identify the object type. ### `mask: Mat` *(read/write)* Mask defining which pixels which belong to the object (in bounding_box_2d and set to 255) and those of the background (set to 0). **Warning:** The mask information is only available for tracked objects (sl.OBJECT_TRACKING_STATE.OK) that have a valid depth. **Warning:** Otherwise, the mask will not be initialized (```mask.is_init() == False```). ### `tracking_state: OBJECT_TRACKING_STATE` *(read/write)* Object tracking state. ### `head_position: npt.NDArray[float]` *(read/write)* 3D centroid of the head of the object (a person). **Note:** It is defined in sl.InitParameters.coordinate_units and expressed in sl.RuntimeParameters.measure3D_reference_frame. **Warning:** Not available with sl.OBJECT_DETECTION_MODEL.MULTI_CLASS_BOX_XXX. ### `velocity: npt.NDArray[float]` *(read/write)* Object 3D velocity. **Note:** It is defined in ```sl.InitParameters.coordinate_units / s``` and expressed in sl.RuntimeParameters.measure3D_reference_frame. ### `bounding_box: npt.NDArray[float][float]` *(read/write)* 3D bounding box of the object represented as eight 3D points. **Note:** It is defined in sl.InitParameters.coordinate_units and expressed in sl.RuntimeParameters.measure3D_reference_frame. 1 ------ 2 / /| 0 ------ 3 | | Object | 6 | |/ 4 ------ 7 ### `id: int` *(read/write)* Object identification number. It is used as a reference when tracking the object through the frames. **Note:** Only available if sl.ObjectDetectionParameters.enable_tracking is activated. **Note:** Otherwise, it will be set to -1. ### `position: npt.NDArray[float]` *(read/write)* Object 3D centroid. **Note:** It is defined in sl.InitParameters.coordinate_units and expressed in sl.RuntimeParameters.measure3D_reference_frame. ### `bounding_box_2d: npt.NDArray[int][int]` *(read/write)* 2D bounding box of the object represented as four 2D points starting at the top left corner and rotation clockwise. **Note:** Expressed in pixels on the original image resolution, ```[0, 0]``` is the top left corner. A ------ B | Object | D ------ C ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # ObjectDetectionFusionParameters Holds the options used to initialize the object detection module of the Fusion ## Properties ### `enable_tracking: bool` *(read/write)* Defines if the object detection will track objects across images flow. Default: True. ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # ObjectDetectionRuntimeParameters Class containing a set of runtime parameters for the object detection module. The default constructor sets all parameters to their default settings. **Note:** Parameters can be adjusted by the user. ## Properties ### `object_class_filter: list[OBJECT_CLASS]` *(read/write)* Defines which object types to detect and track. Default: [] (all classes are tracked) **Note:** Fewer object types can slightly speed up the process since every object is tracked. **Note:** Will output only the selected classes. In order to get all the available classes, the filter list must be empty : object_class_filter = {}; To select a set of specific object classes, like vehicles, persons and animals for instance: object_class_filter = {sl.OBJECT_CLASS.VEHICLE, sl.OBJECT_CLASS.PERSON, sl.OBJECT_CLASS.ANIMAL}; ### `object_tracking_parameters: ObjectTrackingParameters` *(read/write)* Default tracking parameters applied to all object classes. These can be overridden per-class via object_class_tracking_parameters. ### `object_class_tracking_parameters: dict` *(read/write)* Per-class tracking parameters that override the default object_tracking_parameters. Keys are OBJECT_CLASS values, values are ObjectTrackingParameters. ### `object_class_detection_confidence_threshold: dict` *(read/write)* Dictonary of confidence thresholds for each class (can be empty for some classes). **Note:** sl.ObjectDetectionRuntimeParameters.detection_confidence_threshold will be taken as fallback/default value. ### `detection_confidence_threshold: float` *(read/write)* Confidence threshold. From 1 to 100, with 1 meaning a low threshold, more uncertain objects and 99 very few but very precise objects. Default: 20 **Note:** If the scene contains a lot of objects, increasing the confidence can slightly speed up the process, since every object instance is tracked. **Note:** detection_confidence_threshold is used as a fallback when sl::ObjectDetectionRuntimeParameters.object_class_detection_confidence_threshold is partially set. ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # ObjectDetectionSensorsParameters Structure containing a set of parameters for the object detection module in Sensors API. ## Properties ### `prediction_timeout_s: float` *(read/write)* Prediction duration of the ZED SDK when an object is not detected. ### `detection_model: OBJECT_DETECTION_MODEL` *(read/write)* sl::OBJECT_DETECTION_MODEL to use. ### `enable_segmentation: bool` *(read/write)* Whether the object masks will be computed. ### `max_range: float` *(read/write)* Upper depth range for detections. ### `instance_module_id: int` *(read/write)* Id of the module instance. ### `sensors_ids: list[SensorDeviceIdentifier]` *(read/write)* List of sensor id that will be used for this instance. ### `enable_tracking: bool` *(read/write)* Whether the object detection system includes object tracking. ### `filtering_mode: OBJECT_FILTERING_MODE` *(read/write)* Filtering mode that should be applied to raw detections. ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `__init__(self, instance_module_id=0, enable_tracking=True, enable_segmentation=False, detection_model=OBJECT_DETECTION_MODEL.MULTI_CLASS_BOX_FAST, max_range=-1.0, filtering_mode=OBJECT_FILTERING_MODE.NMS3D, prediction_timeout_s=0.2) -> None` Default constructor. :param instance_module_id: Id of the module instance. :param enable_tracking: Whether the object detection system includes object tracking. :param enable_segmentation: Whether the object masks will be computed. :param detection_model: sl::OBJECT_DETECTION_MODEL to use. :param max_range: Upper depth range for detections. :param filtering_mode: Filtering mode that should be applied to raw detections. :param prediction_timeout_s: Prediction duration of the ZED SDK when an object is not detected. --- # ObjectTrackingParameters Class containing tracking parameters for object detection. Used to configure how objects are tracked over time. ## Properties ### `prediction_timeout_s: float` *(read/write)* Prediction timeout in seconds. Duration to keep predicting a track's position after occlusion. A negative value (e.g. -1) lets the ZED SDK interpret the min_confirmation_time_s. Default: -1 ### `min_velocity_threshold: float` *(read/write)* Minimum velocity threshold. Threshold to force an object's velocity to zero (Zero-Snap). A negative value (e.g. -1) lets the ZED SDK interpret the min_confirmation_time_s. Default: -1 ### `object_acceleration_preset: OBJECT_ACCELERATION_PRESET` *(read/write)* Object acceleration preset. Default: OBJECT_ACCELERATION_PRESET.DEFAULT ### `velocity_smoothing_factor: float` *(read/write)* Velocity smoothing factor. Controls the smoothing of the velocity estimation. Values between 0.0 and 1.0. A negative value (e.g. -1) lets the ZED SDK interpret the min_confirmation_time_s. Default: -1 ### `min_confirmation_time_s: float` *(read/write)* Minimum confirmation time required to validate a track. A negative value (e.g. -1) lets the ZED SDK interpret the min_confirmation_time_s. Default: -1 ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # ObjectTrackingParametersProxy Class containing tracking parameters for object detection. Used to configure how objects are tracked over time. ## Properties ### `prediction_timeout_s: float` *(read/write)* Duration to keep predicting a track's position after occlusion. When an object is no longer visible (occluded or out of frame), the tracker will predict its position for this duration before deleting the track. - Short (e.g., 0.2s): Prevents "ghost" objects but may break tracks during short occlusions. - Long (e.g., 2.0s): Maintains ID during long occlusions but may report objects that are gone. A negative value (e.g. -1) lets the ZED SDK interpret the prediction_timeout_s. Default: -1 ### `min_velocity_threshold: float` *(read/write)* Threshold to force an object's velocity to zero. If the calculated speed (m/s) is below this threshold, the object is considered static. This helps eliminate drift on stationary objects. A negative value (e.g. -1) lets the ZED SDK interpret the min_velocity_threshold. Default: -1 ### `object_acceleration_preset: OBJECT_ACCELERATION_PRESET` *(read/write)* Preset defining the expected maximum acceleration of the tracked object. Determines how the ZED SDK interprets object acceleration, affecting tracking behavior and predictions. ### `velocity_smoothing_factor: float` *(read/write)* Values between 0.0 and 1.0. - High value (closer to 1.0): Very smooth, but may lag behind rapid changes. - Low value (closer to 0.0): Very responsive to velocity changes, but may be jittery. - 0.5: ZED SDK base tuning. Balanced smoothing and responsiveness. A negative value (e.g. -1) lets the ZED SDK interpret the velocity_smoothing_factor. Default: -1 ### `min_confirmation_time_s: float` *(read/write)* Minimum confirmation time required to validate a track. The minimum duration (in seconds) an object must be continuously detected before it is reported as a valid track. Helps filter out spurious false positives that appear only briefly. A negative value (e.g. -1) lets the ZED SDK interpret the prediction_timeout_s. Default: -1 ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # Objects Class containing the results of the object detection module. The detected objects are listed in object_list. ## Properties ### `timestamp: Timestamp` *(read/write)* Timestamp corresponding to the frame acquisition. This value is especially useful for the async mode to synchronize the data. ### `object_list: list[ObjectData]` *(read/write)* List of detected objects. ### `is_tracked: bool` *(read/write)* Whether both the object tracking and the world orientation has been setup. Default: False ### `is_new: bool` *(read/write)* Whether object_list has already been retrieved or not. Default: False ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `get_object_data_from_id(self, py_object_data: ObjectData, object_data_id: int) -> bool` Method that looks for a given object id in the current objects list. :param py_object_data: sl.ObjectData to fill if the search succeeded. (Direction: out) :param object_data_id: Id of the sl.ObjectData to search. (Direction: in) :return: True if found, otherwise False. --- # ObjectsBatch Class containing batched data of a detected objects from the object detection module. This class can be used to store trajectories. ## Properties ### `tracking_state: OBJECT_TRACKING_STATE` *(read/write)* Objects tracking state. ### `head_bounding_boxes_2d: npt.NDArray[int][int][int]` *(read-only)* NumPy array of 2D bounding box of the head for each object (person). **Note:** Expressed in pixels on the original image resolution, ```[0, 0]``` is the top left corner. **Warning:** Not available with sl.OBJECT_DETECTION_MODEL.MULTI_CLASS_BOX_XXX. ### `bounding_boxes_2d: npt.NDArray[int][int][int]` *(read-only)* NumPy array of 2D bounding boxes for each object. **Note:** Expressed in pixels on the original image resolution, ```[0, 0]``` is the top left corner. A ------ B | Object | D ------ C ### `id: int` *(read/write)* Id of the batch. ### `head_bounding_boxes: npt.NDArray[float][float][float]` *(read-only)* NumPy array of 3D bounding box of the head for each object (person). **Note:** They are defined in sl.InitParameters.coordinate_units and expressed in sl.RuntimeParameters.measure3D_reference_frame. **Warning:** Not available with sl.OBJECT_DETECTION_MODEL.MULTI_CLASS_BOX_XXX. ### `sublabel: OBJECT_SUBCLASS` *(read/write)* Objects sub-class/sub-category to identify the object type. ### `confidences: npt.NDArray[float]` *(read-only)* NumPy array of confidences for each object. ### `timestamps: list[Timestamp]` *(read-only)* List of timestamps for each object. ### `head_positions: npt.NDArray[float][float]` *(read-only)* NumPy array of 3D centroid of the head for each object (person). **Note:** They are defined in sl.InitParameters.coordinate_units and expressed in sl.RuntimeParameters.measure3D_reference_frame. **Warning:** Not available with sl.OBJECT_DETECTION_MODEL.MULTI_CLASS_BOX_XXX. ### `velocities: npt.NDArray[float][float]` *(read-only)* NumPy array of 3D velocities for each object. ### `positions: npt.NDArray[float][float]` *(read-only)* NumPy array of positions for each object. ### `action_states: list[OBJECT_ACTION_STATE]` *(read-only)* List of action states for each object. ### `label: OBJECT_CLASS` *(read/write)* Objects class/category to identify the object type. ### `bounding_boxes: npt.NDArray[float][float][float]` *(read-only)* NumPy array of 3D bounding boxes for each object. **Note:** They are defined in sl.InitParameters.coordinate_units and expressed in sl.RuntimeParameters.measure3D_reference_frame. 1 ------ 2 / /| 0 ------ 3 | | Object | 6 | |/ 4 ------ 7 ### `position_covariances: npt.NDArray[float][float]` *(read-only)* NumPy array of positions' covariances for each object. ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # Orientation Class representing an orientation/quaternion for the positional tracking module. sl.Orientation is a vector defined as ```[ox, oy, oz, ow]```. ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `init_orientation(self, orient) -> None` Deep copy from another sl.Orientation. :param orient: sl.Orientation to copy. ### `init_vector(self, v0, v1, v2, v3) -> None` Initializes the sl.Orientation with its components. :param v0: ox component. :param v1: oy component. :param v2: oz component. :param v3: ow component. ### `init_rotation(self, rotation) -> None` Initializes the sl.Orientation from an sl.Rotation. It converts the sl.Rotation representation to the sl.Orientation one. :param rotation: sl.Rotation to be used. ### `init_translation(self, tr1, tr2) -> None` Initializes the sl.Orientation from a vector represented by two sl.Translation. :param tr1: First point of the vector. :param tr2: Second point of the vector. ### `set_rotation_matrix(self, py_rotation) -> None` Sets the rotation component of the current sl.Transform from an sl.Rotation. :param py_rotation: sl.Rotation to be used. ### `get_rotation_matrix(self) -> Rotation` Returns the current sl.Orientation as an sl.Rotation. :return: The rotation computed from the orientation data. ### `set_identity(self) -> None` Sets the current sl.Orientation to identity. ### `identity(self, orient=None) -> Orientation` Creates an sl.Orientation initialized to identity. :return: Identity sl.Orientation. ### `set_zeros(self) -> None` Fills the current sl.Orientation with zeros. ### `zeros(self, orient=None) -> Orientation` Creates an sl.Orientation filled with zeros. :return: sl.Orientation filled with zeros. ### `normalize(self) -> None` Normalizes the current sl.Orientation. ### `normalize_orientation(orient) -> Orientation` Gets the normalized sl.Orientation of a given sl.Orientation. :param orient: sl.Orientation to be get the normalized orientation from. :return: Another sl.Orientation object equal to **orient.normalize(). ### `size(self) -> int` Gets the size of the sl.Orientation. :return: Size of the sl.Orientation. ### `get(self) -> npt.NDArray[float]` Returns a numpy array of the Orientation . :return: A numpy array of the Orientation . --- # Plane Class representing a plane defined by a point and a normal, or a plane equation. Other elements can be extracted such as the mesh, the 3D bounds, etc. **Note:** The plane measurements are expressed in reference defined by sl.RuntimeParameters.measure3D_reference_frame. ## Properties ### `type: PLANE_TYPE` *(read/write)* Type of the plane defined by its orientation. **Note:** It is deduced from the gravity vector and is therefore not available with on sl.MODEL.ZED. **Note:** sl.MODEL.ZED will give sl.PLANE_TYPE.UNKNOWN for every planes. ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `get_normal(self) -> npt.NDArray[float]` Gets the plane normal vector. :return: sl.Plane normalized normal vector (NumPy array). ### `get_center(self) -> npt.NDArray[float]` Gets the plane center point :return: sl.Plane center point ### `get_pose(self, py_pose=None) -> Transform` Gets the plane pose relative to the global reference frame. :param py_pose: sl.Transform to fill (or it creates one by default). :return: Transformation matrix (rotation and translation) of the plane pose. **Note:** Can be used to transform the global reference frame center ```(0, 0, 0)``` to the plane center. ### `get_extents(self) -> npt.NDArray[float]` Gets the width and height of the bounding rectangle around the plane contours. :return: Width and height of the bounding plane contours (NumPy array). **Warning:** This value is expressed in the plane reference frame. ### `get_plane_equation(self) -> npt.NDArray[float]` Gets the plane equation. :return: Plane equation coefficients ```[a, b, c, d]``` (NumPy array). **Note:** The plane equation has the following form: ```ax + by + cz = d```. ### `get_bounds(self) -> npt.NDArray[float][float]` Gets the polygon bounds of the plane. :return: Vector of 3D points forming a polygon bounds corresponding to the current visible limits of the plane (NumPy array). ### `extract_mesh(self) -> Mesh` Compute and return the mesh of the bounds polygon. :return: sl::Mesh representing the plane delimited by the visible bounds. ### `get_closest_distance(self, point=[0, 0, 0]) -> float` Gets the distance between the input point and the projected point alongside the normal vector onto the plane (the closest point on the plane). :param point: Point to project into the plane. :return: The Euclidean distance between the input point and the projected point. ### `clear(self) -> None` Clears all the data. --- # PlaneDetectionParameters Class containing a set of parameters for the plane detection functionality. The default constructor sets all parameters to their default settings. **Note:** Parameters can be adjusted by the user. ## Properties ### `normal_similarity_threshold: float` *(read/write)* Controls the spread of plane by checking the angle difference. Default: 15 degrees ### `max_distance_threshold: float` *(read/write)* Controls the spread of plane by checking the position difference. Default: 0.15 meters ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # PointCloudChunk Class representing a sub-point cloud containing local vertices and colors. **Note:** vertices and normals have the same size. ## Properties ### `vertices: npt.NDArray[float]` *(read-only)* NumPy array of vertices. Vertices are defined by a colored 3D point ```[x, y, z, rgba]```. ### `barycenter: npt.NDArray[float]` *(read-only)* 3D centroid of the chunk. ### `normals: npt.NDArray[float]` *(read-only)* NumPy array of normals. Normals are defined by three components ```[nx, ny, nz]```. **Note:** A normal is defined for each vertex. ### `timestamp: int` *(read-only)* Timestamp of the latest update. ### `has_been_updated: bool` *(read-only)* Whether the point cloud chunk has been updated by an inner process. ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `clear(self) -> None` Clears all data. --- # PositionalTrackingFusionParameters Holds the options used for initializing the positional tracking fusion module. ## Properties ### `base_footprint_to_world_transform: Transform` *(read/write)* Position and orientation of the base footprint with respect to the user world. This transform represents a basis change from base footprint coordinate frame to user world coordinate frame ### `base_footprint_to_baselink_transform: Transform` *(read/write)* Position and orientation of the base footprint with respect to the baselink. This transform represents a basis change from base footprint coordinate frame to baselink coordinate frame ### `enable_GNSS_fusion: bool` *(read/write)* This attribute is responsible for enabling or not GNSS positional tracking fusion. Default: False ### `set_gravity_as_origin: bool` *(read/write)* Whether to override 2 of the 3 rotations from base_footprint_to_world_transform using the IMU gravity. Default: False ### `gnss_calibration_parameters: GNSSCalibrationParameters` *(read/write)* Control the VIO / GNSS calibration process. ### `tracking_camera_id: CameraIdentifier` *(read/write)* ID of the camera used for positional tracking. If not specified, will use the first camera called with the subscribe() method. ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # PositionalTrackingLidarParameters Structure containing the options used to enable positional tracking with Lidar. ## Properties ### `enable_real_time_computation: bool` *(read/write)* Whether to compute the motion in real-time or not. Default: True ### `initial_world_transform: Transform` *(read/write)* Default constructor. ### `voxel_size: float` *(read/write)* Voxel size for the ICP. 0.0 means auto. Default: 0.0 ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # PositionalTrackingSensorsParameters Structure containing a set of parameters for positional tracking in Sensors API. ## Properties ### `set_as_static: bool` *(read/write)* Whether to define the camera as static. If True, it will not move in the environment. This allows you to set its position using initial_world_transforms. Default: False ### `set_floor_as_origin: bool` *(read/write)* Initializes the tracking to be aligned with the floor plane to better position the camera in space. Default: False ### `area_file_path: str` *(read/write)* Path of an area localization file that describes the surroundings (saved from a previous tracking session). Default: empty ### `mode: POSITIONAL_TRACKING_MODE` *(read/write)* Positional tracking mode used. Can be used to improve accuracy in some types of scene at the cost of longer runtime. Default: POSITIONAL_TRACKING_MODE.GEN_3 ### `enable_area_memory: bool` *(read/write)* Whether the camera can remember its surroundings. This helps correct positional tracking drift and can be helpful for positioning different cameras relative to one other in space. Default: True ### `enable_imu_fusion: bool` *(read/write)* Whether to enable the IMU fusion. When set to False, only the optical odometry will be used. Default: True ### `enable_pose_smoothing: bool` *(read/write)* Whether to enable smooth pose correction for small drift correction. Default: False ### `set_gravity_as_origin: bool` *(read/write)* Whether to override 2 of the 3 rotations from initial_world_transforms using the IMU gravity. Default: True ### `depth_min_range: float` *(read/write)* Minimum depth used by the ZED SDK for positional tracking. It may be useful for example if any steady objects are in front of the camera and may perturb the positional tracking algorithm. Default: -1 (no minimum depth) ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `__init__(self, enable_area_memory=True, enable_pose_smoothing=False, set_floor_as_origin=False, enable_imu_fusion=True, set_as_static=False, depth_min_range=-1.0, set_gravity_as_origin=True, mode=POSITIONAL_TRACKING_MODE.GEN_3) -> None` Default constructor. --- # PositionalTrackingStatus Lists the different status of the positional tracking ## Properties ### `odometry_status: ODOMETRY_STATUS` *(read/write)* Represents the current state of Visual-Inertial Odometry (VIO) tracking between the previous frame and the current frame. ### `tracking_fusion_status: POSITIONAL_TRACKING_FUSION_STATUS` *(read/write)* Represents the current state of the positional tracking fusion. ### `spatial_memory_status: SPATIAL_MEMORY_STATUS` *(read/write)* Represents the current state of camera tracking in the global map. ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # RecordingLidarParameters Structure containing the options used to record Lidar data. ## Properties ### `format: RECORDING_FORMAT` *(read/write)* Format of the recording. Default: RECORDING_FORMAT.AUTO ### `output_filename: str` *(read/write)* Default constructor. ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # RecordingSensorsParameters Structure containing a set of parameters for the recording module. ## Properties ### `transcode_streaming_input: bool` *(read/write)* Defines whether to decode and re-encode a streaming source. ### `compression_mode: SVO_COMPRESSION_MODE` *(read/write)* Compression mode the recording. ### `target_framerate: int` *(read/write)* Framerate for the recording file. ### `bitrate: int` *(read/write)* Overrides the default bitrate of the SVO file, in kbits/s. ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `__init__(self, video_filenames=None, compression_mode=SVO_COMPRESSION_MODE.H265, bitrate=0, target_framerate=0, transcode_streaming_input=False) -> None` Default constructor. :param video_filenames: Filename of the file to save the recording into. :param compression_mode: Compression mode the recording. :param bitrate: Overrides the default bitrate of the SVO file, in kbits/s. :param target_framerate: Framerate for the recording file. :param transcode_streaming_input: Defines whether to decode and re-encode a streaming source. --- # RecordingStatus Class containing information about the status of the recording. ## Properties ### `is_recording: bool` *(read/write)* Report if the recording has been enabled. ### `current_compression_time: float` *(read/write)* Compression time for the current frame in milliseconds. ### `status: bool` *(read/write)* Status of current frame. True for success or False if the frame could not be written in the SVO file. ### `is_paused: bool` *(read/write)* Report if the recording has been paused. ### `average_compression_time: float` *(read/write)* Average compression time in milliseconds since beginning of recording. ### `number_frames_encoded: int` *(read/write)* Number of frames effectively encoded and written. Might be different from the number of frames ingested. The difference will show the encoder latency ### `number_frames_ingested: int` *(read/write)* Number of frames ingested in SVO encoding/writing. ### `average_compression_ratio: float` *(read/write)* Average compression ratio (% of raw size) since beginning of recording. ### `current_compression_ratio: float` *(read/write)* Compression ratio (% of raw size) for the current frame. ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # Rect Class defining a 2D rectangle with top-left corner coordinates and width/height in pixels. ## Properties ### `height: int` *(read/write)* Height of the rectangle in pixels. ### `x: int` *(read/write)* x coordinates of top-left corner. ### `y: int` *(read/write)* y coordinates of top-left corner. ### `width: int` *(read/write)* Width of the rectangle in pixels. ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `area(self) -> int` Returns the area of the rectangle. ### `is_empty(self) -> bool` Tests if the given sl.Rect is empty (width or/and height is null). ### `contains(self, target: Rect, proper=False) -> bool` Tests if this sl.Rect contains the **target** sl.Rect. :return: True if this rectangle contains the rectangle, otherwise False. **Note:** This method only returns true if the target rectangle is entirely inside this rectangle (not on the edge). ### `is_contained_in_resolution(self, resolution, proper=False) -> bool` Tests if this sl.Rect is contained inside the given **resolution** sl.Resolution. It tests if the current rectangle is contained inside a sl::Rect defined by Rect(0, 0, resolution.width, resolution.height). :return: Ttrue if this rectangle is inside the rectangle defined by Rect(0, 0, resolution.width, resolution.height), otherwise false. **Note:** This method only returns true if this rectangle is entirely inside the rectangle defined by the resolution (not on the edge). ### `is_contained(self, target: Rect, proper=False) -> bool` Tests if this sl.Rect is contained inside the given **target** sl.Rect. :return: True if this rectangle is inside the current **target** sl.Rect, otherwise False. **Note:** This method only returns True if this rectangle is entirely inside the rectangle (not on the edge). --- # RegionOfInterestParameters Class containing a set of parameters for the plane detection functionality. The default constructor sets all parameters to their default settings. **Note:** Parameters can be adjusted by the user. ## Properties ### `image_height_ratio_cutoff: float` *(read/write)* By default consider only the lower half of the image, can be useful to filter out the sky Default: 0.5, correspond to the lower half of the image ### `depth_far_threshold_meters: float` *(read/write)* Filtering how far object in the ROI should be considered, this is useful for a vehicle for instance Default: 2.5 meters ### `auto_apply_module: set[MODULE]` *(read/write)* Once computed the ROI computed will be automatically applied Default: Enabled ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # Resolution Structure containing the width and height of an image. ## Properties ### `height: int` *(read/write)* Height of the image in pixels. ### `width: int` *(read/write)* Width of the image in pixels. ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `area(self) -> int` Area (width * height) of the image. --- # Rotation Class representing a rotation for the positional tracking module. It inherits from the generic sl.Matrix3f class. ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `init_rotation(self, rot: Rotation) -> None` Deep copy from another sl.Rotation. :param rot: sl.Rotation to copy. ### `init_matrix(self, matrix: Matrix3f) -> None` Initializes the sl.Rotation from a sl.Matrix3f. :param matrix: sl.Matrix3f to be used. ### `init_orientation(self, orient: Orientation) -> None` Initializes the sl.Rotation from an sl.Orientation. :param orient: sl.Orientation to be used. ### `init_angle_translation(self, angle: float, axis: Translation) -> None` Initializes the sl.Rotation from an angle and an axis. :param angle: Rotation angle in radian. :param axis: 3D axis to rotate around. ### `set_orientation(self, py_orientation: Orientation) -> None` Sets the sl.Rotation from an sl.Orientation. :param py_orientation: sl.Orientation containing the rotation to set. ### `get_orientation(self) -> Orientation` Returns the sl.Orientation corresponding to the current sl.Rotation. :return: Rotation of the current orientation. ### `get_rotation_vector(self) -> npt.NDArray[float]` Returns the 3x1 rotation vector obtained from 3x3 rotation matrix using Rodrigues formula. :return: Rotation vector (NumPy array) created from the sl.Orientation values. ### `set_rotation_vector(self, input0: float, input1: float, input2: float) -> None` Sets the sl.Rotation from a rotation vector (using Rodrigues' transformation). :param input0: ```rx``` component of the rotation vector. :param input1: ```ry``` component of the rotation vector. :param input2: ```rz``` component of the rotation vector. ### `get_euler_angles(self, radian=True) -> npt.NDArray[float]` Converts the sl.Rotation into Euler angles. :param radian: Whether the angle will be returned in radian or degree. Default: True :return: Euler angles (NumPy array) created from the sl.Rotation values representing the rotations around the X, Y and Z axes using YZX convention. ### `set_euler_angles(self, input0: float, input1: float, input2: float, radian=True) -> None` Sets the sl.Rotation from Euler angles. :param input0: Roll value. :param input1: Pitch value. :param input2: Yaw value. :param radian: Whether the angle is in radian or degree. Default: True --- # RuntimeSensorsParameters Structure containing the runtime parameters used by Sensors. ## Properties ### `depth_confidence_threshold: dict` *(read/write)* Depth confidence threshold per sensor. Dictionary mapping SensorDeviceIdentifier to int threshold values. ### `reference_frame: SENSORS_REFERENCE_FRAME` *(read/write)* Reference frame for point cloud measures. Defines the coordinate frame in which point clouds will be returned. - SENSORS_REFERENCE_FRAME.SENSOR : Points are in each sensor's local frame (identity transform). - SENSORS_REFERENCE_FRAME.BASELINK : Points are transformed by the sensor pose (extrinsic calibration). - SENSORS_REFERENCE_FRAME.WORLD : Points are transformed to world frame using sensor pose + positional tracking. Default: SENSOR (no transformation applied). ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # SVOData Class containing SVO data to be ingested/retrieved to/from SVO. ## Properties ### `key: str` *(read/write)* Key of the data. ### `timestamp_ns: Timestamp` *(read/write)* Timestamp of the data. ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `get_content_as_string(self) -> str` Get the content of the sl.SVOData as a string. :return: The content of the sl.SVOData as a string. ### `set_string_content(self, data: str) -> str` Set the content of the sl.SVOData as a string. \param data The string data content to set. --- # SensorDeviceIdentifier Structure containing information about a sensor device (camera or lidar) managed by the Sensors class. ## Properties ### `sensor_type: SENSORS_TYPE` *(read/write)* Type of the sensor. ### `sensor_name: str` *(read/write)* Custom name of the camera. ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `__init__(self, name='', type=SENSORS_TYPE.CAMERA) -> None` Default constructor. :param name: Custom name of the camera. :param type: Type of the sensor. ### `get_id(self) -> None` Returns the unique ID of the sensor. ### `get_serial_number(self) -> None` Returns the serial number of the sensor. --- # SensorList Structure containing lists of all available sensor devices. This structure aggregates device information from all sensor types: - ZED stereo cameras (ZED, ZED 2, ZED 2i, ZED X, ZED X Mini) - ZED One cameras - Lidar devices ## Properties ### `cameras_one: list[DeviceProperties]` *(read-only)* List of connected ZED One cameras. ### `cameras: list[DeviceProperties]` *(read-only)* List of connected ZED stereo cameras (ZED, ZED 2, ZED 2i, ZED X, ZED X Mini). ### `lidars: list[LidarDeviceProperties]` *(read-only)* List of connected Lidar devices. ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # SensorParameters Class containing information about a single sensor available in the current device. Information about the camera sensors is available in the sl.CameraInformation struct returned by sl.Camera.get_camera_information(). **Note:** This class is meant to be used as a read-only container. **Note:** Editing any of its fields will not impact the ZED SDK. ## Properties ### `sensor_range: npt.NDArray[float]` *(read-only)* Range (NumPy array) of the sensor (minimum: `sensor_range[0]`, maximum: `sensor_range[1]`). ### `random_walk: float` *(read/write)* Random walk derived from the Allan Variance given as continuous (frequency-independent). **Note:** The units will be expressed in ```sensor_unit / √(Hz)```. **Note:** `NAN` if the information is not available. ### `sensor_unit: SENSORS_UNIT` *(read-only)* Unit of the sensor. ### `resolution: float` *(read/write)* Resolution of the sensor. ### `sensor_type: SENSOR_TYPE` *(read-only)* Type of the sensor. ### `noise_density: float` *(read/write)* White noise density given as continuous (frequency-independent). **Note:** The units will be expressed in ```sensor_unit / √(Hz)```. **Note:** `NAN` if the information is not available. ### `is_available: bool` *(read-only)* Whether the sensor is available in your camera. ### `sampling_rate: float` *(read/write)* Sampling rate (or ODR) of the sensor. ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `_set(self) -> None` ### `set_sensor_range(self, value1: float, value2: float) -> None` Sets the minimum and the maximum values of the sensor range. \param float value1 : Minimum of the range to set. \param float value2 : Maximum of the range to set. --- # Sensors Class for managing multiple sensors (Cameras, Lidars) and fusing their data. ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `get_sensor_list() -> SensorList` Returns the list of available sensors. ### `get_streaming_sensor_list() -> StreamingSensorList` Returns the list of available streaming sensors. ### `init(self, init_parameters=None) -> SENSORS_ERROR_CODE` Initializes the Sensors instance. ### `add(self, py_init, camera_identifier_out=None) -> SENSORS_ERROR_CODE` Adds a camera or LIDAR to the Sensors instance. ### `remove(self, unique_identifier) -> SENSORS_ERROR_CODE` Stops a sensor and removes it from the instance. ### `read(self) -> SENSORS_ERROR_CODE` Reads the latest images and IMU from all sensors and rectifies the images. ### `process(self) -> SENSORS_ERROR_CODE` Processes data from all sensors. ### `get_error_codes(self) -> tuple` Gets the list of individual ERROR_CODE returned by each sensor in the last function call. :return: A tuple of (SENSORS_ERROR_CODE, dict[SensorDeviceIdentifier, ERROR_CODE]). ### `get_process_error_codes(self) -> tuple` Gets the list of individual ERROR_CODE returned by each sensor in the last read/process function call. :return: A tuple of (SENSORS_ERROR_CODE, dict[SensorDeviceIdentifier, ERROR_CODE]). ### `set_runtime_sensors_parameters(self, params) -> SENSORS_ERROR_CODE` Sets the runtime parameters for Sensors. :param params: The runtime parameters. :return: SENSORS_ERROR_CODE indicating success or failure. ### `retrieve_image_batched(self, view=VIEW.LEFT, mem_type=MEM.CPU, image_size=None, sensors_ids=None) -> tuple` Returns the VIEW of all the specified sensors. :param view: The view to retrieve. :param mem_type: The memory type (CPU/GPU). :param image_size: The resolution of the output images. :param sensors_ids: List of sensor identifiers to retrieve. Empty list means all sensors. :return: A tuple of (SENSORS_ERROR_CODE, dict[SensorDeviceIdentifier, Mat]). ### `retrieve_measure_batched(self, measure=MEASURE.DEPTH, mem_type=MEM.CPU, image_size=None, sensors_ids=None) -> tuple` Returns the MEASURE of all the specified sensors. :param measure: The measure to retrieve. :param mem_type: The memory type (CPU/GPU). :param image_size: The resolution of the output measures. :param sensors_ids: List of sensor identifiers to retrieve. Empty list means all sensors. :return: A tuple of (SENSORS_ERROR_CODE, dict[SensorDeviceIdentifier, Mat]). ### `retrieve_lidar_measure_batched(self, measure=LIDAR_MEASURE.XYZ, mem_type=MEM.CPU, image_size=None, sensors_ids=None) -> tuple` Returns the LIDAR_MEASURE of all the specified sensors (Lidar). :param measure: The lidar measure to retrieve. :param mem_type: The memory type (CPU/GPU). :param image_size: The resolution of the output measures. :param sensors_ids: List of sensor identifiers to retrieve. Empty list means all sensors. :return: A tuple of (SENSORS_ERROR_CODE, dict[SensorDeviceIdentifier, Mat]). ### `get_motion_sensors_data_batched(self, reference_time=TIME_REFERENCE.IMAGE, sensors_ids=None) -> tuple` Returns the SensorsData (IMU, magnetometer, barometer) of all the specified sensors. :param reference_time: The time reference. :param sensors_ids: List of sensor identifiers to retrieve. Empty list means all sensors. :return: A tuple of (SENSORS_ERROR_CODE, dict[SensorDeviceIdentifier, SensorsData]). ### `get_current_fps_batched(self, sensors_ids=None) -> tuple` Returns the current compute FPS of all the specified sensors. :param sensors_ids: List of sensor identifiers to query. Empty list means all sensors. :return: A tuple of (SENSORS_ERROR_CODE, dict[SensorDeviceIdentifier, float]). ### `get_frame_dropped_count_batched(self, sensors_ids=None) -> tuple` Returns the frame dropped count of all the specified sensors. :param sensors_ids: List of sensor identifiers to query. Empty list means all sensors. :return: A tuple of (SENSORS_ERROR_CODE, dict[SensorDeviceIdentifier, int]). ### `get_timestamp_batched(self, reference_time=TIME_REFERENCE.IMAGE, sensors_ids=None) -> tuple` Returns the timestamp of all the specified sensors. :param reference_time: The time reference (IMAGE or CURRENT). :param sensors_ids: List of sensor identifiers to query. Empty list means all sensors. :return: A tuple of (SENSORS_ERROR_CODE, dict[SensorDeviceIdentifier, Timestamp]). ### `get_health_status_batched(self, sensors_ids=None) -> tuple` Returns the health status of all the specified sensors. :param sensors_ids: List of sensor identifiers to query. Empty list means all sensors. :return: A tuple of (SENSORS_ERROR_CODE, dict[SensorDeviceIdentifier, HealthStatus]). ### `get_position_batched(self, reference_frame=SENSORS_REFERENCE_FRAME.WORLD, sensors_ids=None) -> tuple` Returns the position and tracking state of all the specified sensors. :param reference_frame: The reference frame (WORLD or CAMERA). :param sensors_ids: List of sensor identifiers to query. Empty list means all sensors. :return: A tuple of (SENSORS_ERROR_CODE, dict[SensorDeviceIdentifier, tuple[Pose, POSITIONAL_TRACKING_STATE]]). ### `retrieve_image(self, mat, view=VIEW.LEFT, mem_type=MEM.CPU, image_size=None, unique_identifier=None) -> SENSORS_ERROR_CODE` Returns the current VIEW of the specified camera. ### `retrieve_measure(self, mat, measure=MEASURE.DEPTH, mem_type=MEM.CPU, image_size=None, unique_identifier=None) -> SENSORS_ERROR_CODE` Returns the current MEASURE of the specified camera. ### `set_sensor_pose(self, pose, unique_identifier=None) -> SENSORS_ERROR_CODE` Updates the sensor pose relative to the system frame. ### `get_sensor_pose(self, pose, unique_identifier=None) -> SENSORS_ERROR_CODE` Gets the sensor pose relative to the system frame. ### `get_sensors_id(self) -> None` Gets the list of all current active sensors IDs. ### `get_current_fps(self, unique_identifier=None) -> None` Returns the current compute FPS of the specified camera. ### `get_frame_dropped_count(self, unique_identifier=None) -> None` Returns the frame dropped count of the specified camera. ### `get_camera_information(self, image_size=None, unique_identifier=None) -> dict` Returns the CameraInformation associated with the camera being used. ### `get_svo_position(self, unique_identifier=None) -> None` Returns the current playback position in the SVO file. ### `set_svo_position(self, position, unique_identifier=None) -> SENSORS_ERROR_CODE` Sets the playback cursor to the desired frame number in the SVO file. ### `get_svo_number_of_frames(self, unique_identifier=None) -> None` Returns the number of frames in the SVO file. ### `sync_svo(self, timestamp=None) -> SENSORS_ERROR_CODE` Synchronizes all sensors when the input used is SVO/OSF files. ### `enable_recording(self, recording_parameters) -> SENSORS_ERROR_CODE` Enables the recording module. ### `get_recording_status(self, sensors_id=None) -> RecordingStatus` Returns the recording status for a specific sensor. ### `pause_recording(self, status=True, sensors_id=None) -> None` Pauses or resumes the recording. ### `disable_recording(self, sensors_ids=None) -> None` Disables recording for the specified sensors. ### `enable_streaming(self, streaming_parameters=None) -> SENSORS_ERROR_CODE` Enables the streaming module. ### `disable_streaming(self, cameras_ids=None) -> None` Disables streaming for the specified sensors. ### `enable_object_detection(self, object_detection_parameters) -> SENSORS_ERROR_CODE` Enables the object detection module. ### `set_object_detection_runtime_parameters(self, params, instance_id=0, cam_identifiers=None) -> SENSORS_ERROR_CODE` Sets the runtime parameters of the object detection module. ### `retrieve_objects(self, objects, sensors_id=None, instance_module_id=0) -> SENSORS_ERROR_CODE` Retrieves the objects data of the specified object detection instance and sensor. ### `disable_object_detection(self, instance_module_id=0) -> SENSORS_ERROR_CODE` Disables the object detection module instance. ### `enable_body_tracking(self, body_tracking_parameters) -> SENSORS_ERROR_CODE` Enables the body tracking module. ### `set_body_tracking_runtime_parameters(self, params, instance_id=0, cam_identifiers=None) -> SENSORS_ERROR_CODE` Sets the runtime parameters of the body tracking module. ### `retrieve_bodies(self, bodies, sensors_id=None, instance_module_id=0) -> SENSORS_ERROR_CODE` Retrieves the bodies data of the specified body tracking instance and sensor. ### `disable_body_tracking(self, instance_module_id=0) -> SENSORS_ERROR_CODE` Disables the body tracking module instance. ### `enable_positional_tracking(self, tracking_parameters=PositionalTrackingSensorsParameters(), sensors_id=None) -> SENSORS_ERROR_CODE` Enables positional tracking for the sensors in the Sensors instance. ### `get_position(self, camera_pose, reference_frame=SENSORS_REFERENCE_FRAME.WORLD, unique_identifier=None) -> POSITIONAL_TRACKING_STATE` Gets the position of the specified camera. ### `reset_positional_tracking(self, path, sensors_ids=None) -> SENSORS_ERROR_CODE` Resets positional tracking for the specified sensors. ### `get_positional_tracking_status(self, sensors_id=None) -> PositionalTrackingStatus` Returns the positional tracking status for a specific sensor. ### `save_area_map(self, area_file_path, sensors_id=None) -> SENSORS_ERROR_CODE` Saves the current area learning file. ### `get_area_export_state(self, sensors_id=None) -> AREA_EXPORTING_STATE` Returns the state of the spatial memory export process. ### `get_motion_sensors_data(self, data, reference_time=TIME_REFERENCE.IMAGE, unique_identifier=None) -> SENSORS_ERROR_CODE` Returns the SensorsData (IMU, magnetometer, barometer) of the specified sensor. ### `update_self_calibration(self, unique_identifier=None) -> None` Performs a new self-calibration process for the specified camera. ### `get_camera_settings(self, settings, sensors_id=None) -> None` Returns the current value of the requested camera setting. ### `get_camera_settings_range(self, settings, sensors_id=None) -> None` Returns the range for the specified camera setting. ### `is_camera_setting_supported(self, setting, sensors_id=None) -> None` Checks if the video setting is supported by the camera. ### `set_camera_settings(self, settings, value=-1, sensors_id=None) -> SENSORS_ERROR_CODE` Sets the value of the requested camera setting. ### `get_camera_settings_min_max(self, settings, sensors_id=None) -> None` Returns the current min/max values of the requested camera setting. Works with AUTO_EXPOSURE_TIME_RANGE, AUTO_ANALOG_GAIN_RANGE, AUTO_DIGITAL_GAIN_RANGE. :param settings: The setting to retrieve. :param sensors_id: The sensor identifier. :return: A tuple of (SENSORS_ERROR_CODE, min_val, max_val). ### `set_camera_settings_min_max(self, settings, min_val, max_val, sensors_id=None) -> SENSORS_ERROR_CODE` Sets the min/max values for the requested camera setting. Works with AUTO_EXPOSURE_TIME_RANGE, AUTO_ANALOG_GAIN_RANGE, AUTO_DIGITAL_GAIN_RANGE. :param settings: The setting to set. :param min_val: The minimum value. :param max_val: The maximum value. :param sensors_id: The sensor identifier. :return: SENSORS_ERROR_CODE indicating success or failure. ### `get_camera_settings_roi(self, settings, roi, side=SIDE.BOTH, sensors_id=None) -> SENSORS_ERROR_CODE` Returns the AEC_AGC_ROI for the specified camera setting. :param settings: The setting to retrieve (should be AEC_AGC_ROI). :param roi: The Rect object to store the ROI. :param side: The side (LEFT, RIGHT, or BOTH). :param sensors_id: The sensor identifier. :return: SENSORS_ERROR_CODE indicating success or failure. ### `set_camera_settings_roi(self, settings, roi, side=SIDE.BOTH, reset=False, sensors_id=None) -> SENSORS_ERROR_CODE` Sets the AEC_AGC_ROI for the specified camera setting. :param settings: The setting to set (should be AEC_AGC_ROI). :param roi: The ROI to set. :param side: The side (LEFT, RIGHT, or BOTH). :param reset: Whether to reset the ROI to default. :param sensors_id: The sensor identifier. :return: SENSORS_ERROR_CODE indicating success or failure. ### `set_region_of_interest(self, roi_mask, modules=None, unique_identifier=None) -> SENSORS_ERROR_CODE` Defines a region of interest to focus on for all the SDK. ### `get_region_of_interest(self, roi_mask, image_size=None, module=MODULE.ALL, unique_identifier=None) -> SENSORS_ERROR_CODE` Gets the previously set or computed region of interest. ### `start_region_of_interest_auto_detection(self, roi_param=None, unique_identifier=None) -> SENSORS_ERROR_CODE` Starts the auto detection of a region of interest. ### `get_region_of_interest_auto_detection_status(self, unique_identifier=None) -> None` Returns the status of the automatic Region of Interest Detection. ### `get_svo_position_at_timestamp(self, timestamp, unique_identifier=None) -> None` Retrieves the frame index within the SVO file corresponding to the provided timestamp. ### `set_svo_position_at_timestamp(self, timestamp) -> SENSORS_ERROR_CODE` Seeks all sensors to a specific timestamp. ### `ingest_data_into_svo(self, data, unique_identifier=None) -> SENSORS_ERROR_CODE` Ingest custom user SVOData in a SVO file. ### `disable_positional_tracking(self, area_file_path='') -> None` Disables positional tracking. ### `is_positional_tracking_enabled(self) -> bool` Checks if positional tracking is enabled. ### `close(self) -> SENSORS_ERROR_CODE` Closes the Sensors instance, releasing all resources and cameras. --- # SensorsConfiguration Class containing information about all the sensors available in the current device. Information about the camera sensors is available in the sl.CameraInformation struct returned by sl.Camera.get_camera_information(). **Note:** This class is meant to be used as a read-only container. **Note:** Editing any of its fields will not impact the ZED SDK. ## Properties ### `firmware_version: int` *(read-only)* Firmware version of the sensor module. **Note:** 0 if no sensors are available (sl.MODEL.ZED). ### `gyroscope_parameters: SensorParameters` *(read-only)* Configuration of the gyroscope. ### `accelerometer_parameters: SensorParameters` *(read-only)* Configuration of the accelerometer. ### `magnetometer_parameters: SensorParameters` *(read-only)* Configuration of the magnetometer. ### `imu_magnetometer_transform: Transform` *(read-only)* Magnetometer to IMU transform matrix. **Note:** It contains rotation and translation between IMU frame and magnetometer frame. ### `barometer_parameters: SensorParameters` *(read-only)* Configuration of the barometer. ### `camera_imu_transform: Transform` *(read-only)* IMU to left camera transform matrix. **Note:** It contains the rotation and translation between the IMU frame and camera frame. ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `is_sensor_available(self, sensor_type) -> bool` Checks if a sensor is available on the device. :param sensor_type: Sensor type to check. :return: True if the sensor is available on the device, otherwise False. --- # SpatialMappingFusionParameters Holds the options used for initializing the positional tracking fusion module. ## Properties ### `decay: float` *(read/write)* Adjust the weighting factor for the current depth during the integration process. Setting it to 0 discards all previous data and solely integrates the current depth. Default: 1, which results in the complete integration and fusion of the current depth with the previously integrated depth. ### `max_memory_usage: int` *(read/write)* The maximum CPU memory (in MB) allocated for the meshing process. Default: 2048 MB ### `disparity_std: float` *(read/write)* Control the disparity noise (standard deviation) in px. set a very small value (<0.1) if the depth map of the scene is accurate. Set a big value (>0.5) if the depth map is noisy. Default: 0.3 ### `use_chunk_only: bool` *(read/write)* Set to false if you want to ensure consistency between the mesh and its inner chunk data. **Note:** Updating the mesh is time-consuming. Setting this to true results in better performance. Default: False ### `resolution_meter: float` *(read/write)* Spatial mapping resolution in meters. Default: 0.05 m ### `map_type: SPATIAL_MAP_TYPE` *(read/write)* The type of spatial map to be created. This dictates the format that will be used for the mapping(e.g. mesh, point cloud). See SPATIAL_MAP_TYPE Default: SPATIAL_MAP_TYPE.MESH. ### `stability_counter: int` *(read/write)* Control the integration rate of the current depth into the mapping process. This parameter controls how many times a stable 3D points should be seen before it is integrated into the spatial mapping. Default: 0, this will define the stability counter based on the mesh resolution, the higher the resolution, the higher the stability counter. ### `enable_forget_past: bool` *(read/write)* Default: false ### `range_meter: float` *(read/write)* Depth range in meters. Can be different from the value set by sl::InitParameters::depth_maximum_distance. Default: 0. In this case, the range is computed from resolution_meter and from the current internal parameters to fit your application. ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # SpatialMappingParameters Class containing a set of parameters for the spatial mapping module. The default constructor sets all parameters to their default settings. **Note:** Parameters can be adjusted by the user. ## Properties ### `max_memory_usage: int` *(read/write)* The maximum CPU memory (in MB) allocated for the meshing process. Default: 2048 ### `save_texture: bool` *(read/write)* Whether to save the texture. If set to true, you will be able to apply the texture to your mesh after it is created. Default: False **Note:** This option will consume more memory. **Note:** This option is only available for sl.SPATIAL_MAP_TYPE.MESH. ### `allowed_range: npt.NDArray[float]` *(read-only)* The maximum depth allowed by spatial mapping: - **allowed_range.first is the minimum value allowed - **allowed_range.second is the maximum value allowed ### `stability_counter: int` *(read/write)* Control the integration rate of the current depth into the mapping process. This parameter controls how many times a stable 3D points should be seen before it is integrated into the spatial mapping. Default: 0 (this will define the stability counter based on the mesh resolution, the higher the resolution, the higher the stability counter) ### `allowed_resolution: npt.NDArray[float]` *(read-only)* The resolution allowed by the spatial mapping: - **allowed_resolution.first is the minimum value allowed - **allowed_resolution.second is the maximum value allowed ### `resolution_meter: float` *(read/write)* Spatial mapping resolution in meters. Default: 0.05 **Note:** It should fit allowed_resolution. ### `use_chunk_only: bool` *(read/write)* Whether to only use chunks. If set to False, you will ensure consistency between the mesh and its inner chunk data. Default: False **Note:** Updating the mesh is time-consuming. **Note:** Setting this to True results in better performance. ### `reverse_vertex_order: bool` *(read/write)* Whether to inverse the order of the vertices of the triangles. If your display process does not handle front and back face culling, you can use this to correct it. Default: False **Note:** This option is only available for sl.SPATIAL_MAP_TYPE.MESH. ### `map_type: SPATIAL_MAP_TYPE` *(read/write)* The type of spatial map to be created. This dictates the format that will be used for the mapping (e.g. mesh, point cloud). See sl.SPATIAL_MAP_TYPE. ### `range_meter: float` *(read/write)* Depth range in meters. Can be different from the value set by sl.InitParameters.depth_maximum_distance. **Note:** Set to 0 by default. In this case, the range is computed from resolution_meter and from the current internal parameters to fit your application. ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `set_resolution(self, resolution=MAPPING_RESOLUTION.HIGH) -> None` Sets the resolution to a sl.MAPPING_RESOLUTION preset. :param resolution: The desired sl.MAPPING_RESOLUTION. Default: sl.MAPPING_RESOLUTION.HIGH ### `set_range(self, mapping_range=MAPPING_RANGE.AUTO) -> None` Sets the range to a sl.MAPPING_RANGE preset. :param mapping_range: The desired sl.MAPPING_RANGE. Default: sl.MAPPING_RANGE::AUTO ### `get_range_preset(self, mapping_range=MAPPING_RANGE.AUTO) -> float` Returns the value corresponding to a sl.MAPPING_RANGE preset in meters. :param mapping_range: The desired sl.MAPPING_RANGE. Default: sl.MAPPING_RANGE::AUTO :return: The value of **mapping_range in meters. ### `get_resolution_preset(self, resolution=MAPPING_RESOLUTION.HIGH) -> float` Returns the value corresponding to a sl.MAPPING_RESOLUTION preset in meters. :param resolution: The desired sl.MAPPING_RESOLUTION. Default: sl.MAPPING_RESOLUTION.HIGH :return: The value of **resolution in meters. ### `get_recommended_range(self, resolution, py_cam: Camera) -> float` Returns the recommended maximum depth value corresponding to a resolution. :param resolution: The desired resolution, either defined by a sl.MAPPING_RESOLUTION preset or a resolution value in meters. :param py_cam: The sl.Camera object which will run the spatial mapping. :return: The maximum value of depth in meters. ### `save(self, filename: str) -> bool` Saves the current set of parameters into a file to be reloaded with the load() method. :param filename: Name of the file which will be created to store the parameters (extension '.yml' will be added if not set). :return: True if the file was successfully saved, otherwise False. **Warning:** For security reasons, the file must not already exist. **Warning:** In case a file already exists, the method will return False and existing file will not be updated. ### `load(self, filename: str) -> bool` Loads a set of parameters from the values contained in a previously save() "saved" file. :param filename: Path to the file from which the parameters will be loaded (extension '.yml' will be added at the end of the filename if not detected). :return: True if the file was successfully loaded, otherwise False. --- # StreamingProperties Class containing information about the properties of a streaming device. ## Properties ### `current_bitrate: int` *(read/write)* Current bitrate of encoding of the streaming device. Default: 0 ### `camera_model: MODEL` *(read/write)* Model of the streaming device. Default: sl.MODEL.LAST ### `port: int` *(read/write)* Streaming port of the streaming device. Default: 0 ### `codec: STREAMING_CODEC` *(read/write)* Current codec used for compression in streaming device. Default: sl.STREAMING_CODEC.H265 ### `serial_number: int` *(read/write)* Serial number of the streaming camera. Default: 0 ### `ip: str` *(read/write)* IP address of the streaming device. Default: "" ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # StreamingSensorList Structure containing lists of all available streaming sensor devices. This structure aggregates streaming device information from all sensor types: - ZED stereo cameras (ZED, ZED 2, ZED 2i, ZED X, ZED X Mini) - ZED One cameras - Lidar devices ## Properties ### `cameras_one: list[StreamingProperties]` *(read-only)* List of streaming ZED One cameras. ### `cameras: list[StreamingProperties]` *(read-only)* List of streaming ZED stereo cameras (ZED, ZED 2, ZED 2i, ZED X, ZED X Mini). ### `lidars: list[LidarDeviceProperties]` *(read-only)* List of streaming Lidar devices. ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # StreamingSensorsParameters Structure containing a set of parameters for the streaming module. ## Properties ### `chunk_size: int` *(read/write)* Size of a single chunk. ### `adaptative_bitrate: bool` *(read/write)* Defines whether the adaptive bitrate is enable. ### `target_framerate: int` *(read/write)* Framerate for the streaming output. ### `gop_size: int` *(read/write)* GOP size in number of frames. ### `port: int` *(read/write)* Port used for streaming. ### `codec: STREAMING_CODEC` *(read/write)* Encoding used for streaming. ### `bitrate: int` *(read/write)* Streaming bitrate (in Kbits/s) used for streaming. ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `__init__(self, codec=STREAMING_CODEC.H265, port=30000, bitrate=0, gop_size=-1, adaptative_bitrate=False, chunk_size=16084, target_framerate=0) -> None` Default constructor. :param codec: Encoding used for streaming. :param port: Port used for streaming. :param bitrate: Streaming bitrate (in Kbits/s) used for streaming. :param gop_size: GOP size in number of frames. :param adaptative_bitrate: Defines whether the adaptive bitrate is enable. :param chunk_size: Size of a single chunk. :param target_framerate: Framerate for the streaming output. --- # SynchronizationParameter Class containing GNSS data to be used for positional tracking as prior. ## Properties ### `windows_size: double` *(read/write)* Size of synchronization windows in milliseconds. The synchronization window is used by the synchronizer to return all data present inside the current synchronization window. For efficient fusion, the synchronization window size is expected to be equal to the period of the lowest source of data. If not provided, the fusion SDK will compute it from the data's sources. ### `keep_last_data: bool` *(read/write)* Determines whether to include the last data returned by a source in the final synchronized data. If the keep_last_data parameter is set to true and no data is present in the current synchronization window, the last data returned by the source will be included in the final synchronized data. This ensures continuity even in the absence of fresh data. ### `data_source_timeout: double` *(read/write)* Duration in milliseconds before considering a data source inactive if no more data is present. The data_source_timeout parameter specifies the duration to wait before considering a data source as inactive if no new data is received within the specified time frame. ### `maximum_lateness: double` *(read/write)* Maximum duration in milliseconds allowed for data to be considered as the last data. The maximum_lateness parameter sets the maximum duration within which data can be considered as the last available data. If the duration between the last received data and the current synchronization window exceeds this value, the data will not be included as the last data in the final synchronized output. ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # TemperatureData Class containing data from the temperature sensors. ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `get(self, location) -> float` Gets the temperature value at a temperature sensor location. :param location: Location of the temperature sensor to request. :return: Temperature at the requested location. --- # Tensor Class representing a Tensor, used for inference. ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `alloc(self, params) -> None` Allocates the Tensor memory. :param params: Parameters defining the Tensor creation. ### `get_dims(self) -> None` Returns the dimensions of the Tensor. :return: A vector containing the size of each dimension (e.g., {Batch, Channels, Height, Width} for NCHW). ### `get_element_count(self) -> None` Returns the total number of elements in the Tensor. :return: The product of all dimensions. ### `get_parameters(self) -> None` Returns the parameters used to create or define the Tensor. :return: The TensorParameters associated with this Tensor. --- # TensorParameters Class containing the parameters of a Tensor ## Properties ### `scale: list[float]` *(read/write)* Scale factor applied to the pixel values before normalization. ### `memory_type: MEM` *(read/write)* Where the Tensor should be stored (CPU or GPU). ### `pixel_type: TENSOR_PIXEL_TYPE` *(read/write)* Pixel data type for the Tensor elements. **Note:** Specifies the underlying data type: UCHAR (8-bit), FLOAT (32-bit), or HALF (16-bit). Default: TENSOR_PIXEL_TYPE.FLOAT. ### `target_size: Resolution` *(read/write)* Target size for the input image (Width, Height). Default: (640,640). ### `batch_size: int` *(read/write)* Number of images in the batch. ### `layout: TENSOR_LAYOUT` *(read/write)* Desired memory layout for the output Tensor. **Note:** NCHW (planar) is common for PyTorch models. **Note:** NHWC (interleaved) is common for TensorFlow models. ### `stretch: bool` *(read/write)* If true, stretches the image to target_size. If false, keeps aspect ratio and applies letterboxing (padding). ### `std: list[float]` *(read/write)* Normalization parameter: Standard Deviation. **Note:** Pixel = (Pixel * Scale - Mean) / Std. Default: ImageNet Standard [0.229, 0.224, 0.225]. ### `mean: list[float]` *(read/write)* Normalization parameter: Mean. **Note:** Pixel = (Pixel * Scale - Mean) / Std. Default: ImageNet Standard [0.485, 0.456, 0.406]. ### `color_format: TENSOR_COLOR_FORMAT` *(read/write)* Desired color format for the output Tensor. ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `get_pixel_size(self) -> int` Returns the size in bytes of a single pixel element based on pixel_type. :return: The size in bytes (1 for UCHAR, 2 for HALF, 4 for FLOAT). ### `get_requested_channels(self) -> int` Returns the number of channels associated with the color_format. :return: The number of channels. --- # Timestamp Structure representing timestamps with utilities. ## Properties ### `data_ns: int` *(read/write)* Timestamp in nanoseconds. ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `get_nanoseconds(self) -> int` Returns the timestamp in nanoseconds. ### `get_microseconds(self) -> int` Returns the timestamp in microseconds. ### `get_milliseconds(self) -> int` Returns the timestamp in milliseconds. ### `get_seconds(self) -> int` Returns the timestamp in seconds. ### `set_nanoseconds(self, t_ns: int) -> None` Sets the timestamp to a value in nanoseconds. ### `set_microseconds(self, t_us: int) -> None` Sets the timestamp to a value in microseconds. ### `set_milliseconds(self, t_ms: int) -> None` Sets the timestamp to a value in milliseconds. ### `set_seconds(self, t_s: int) -> None` Sets the timestamp to a value in seconds. ### `from_nanoseconds(t_ns: int) -> None` Create a Timestamp from nanoseconds. ### `from_microseconds(t_us: int) -> None` Create a Timestamp from microseconds. ### `from_milliseconds(t_ms: int) -> None` Create a Timestamp from milliseconds. ### `from_seconds(t_s: int) -> None` Create a Timestamp from seconds. --- # Transform Class representing a transformation (translation and rotation) for the positional tracking module. It can be used to create any type of Matrix4x4 or sl::Matrix4f that must be specifically used for handling a rotation and position information (OpenGL, Tracking, etc.). It inherits from the generic sl::Matrix4f class. ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `init_transform(self, motion) -> None` Deep copy from another sl.Transform. :param motion: sl.Transform to copy. ### `init_matrix(self, matrix: Matrix4f) -> None` Initializes the sl.Transform from a sl.Matrix4f. :param matrix: sl.Matrix4f to be used. ### `init_rotation_translation(self, rot: Rotation, tr: Translation) -> None` Initializes the sl.Transform from an sl.Rotation and a sl.Translation. :param rot: sl.Rotation to be used. :param tr: sl.Translation to be used. ### `init_orientation_translation(self, orient: Orientation, tr: Translation) -> None` Initializes the sl.Transform from an sl.Orientation and a sl.Translation. :param orient: Orientation to be used :param tr: Translation to be used ### `set_rotation_matrix(self, py_rotation: Rotation) -> None` Sets the rotation component of the current sl.Transform from an sl.Rotation. :param py_rotation: sl.Rotation to be used. ### `get_rotation_matrix(self) -> Rotation` Returns the sl.Rotation corresponding to the current sl.Transform. :return: sl.Rotation created from the sl.Transform values. **Warning:** The given sl.Rotation contains a copy of the sl.Transform values. ### `set_translation(self, py_translation: Translation) -> None` Sets the translation component of the current sl.Transform from an sl.Translation. :param py_translation: sl.Translation to be used. ### `get_translation(self) -> Translation` Returns the sl.Translation corresponding to the current sl.Transform. :return: sl.Translation created from the sl.Transform values. **Warning:** The given sl.Translation contains a copy of the sl.Transform values. ### `set_orientation(self, py_orientation: Orientation) -> None` Sets the orientation component of the current sl.Transform from an sl.Orientation. :param py_orientation: sl.Orientation to be used. ### `get_orientation(self) -> Orientation` Returns the sl.Orientation corresponding to the current sl.Transform. :return: sl.Orientation created from the sl.Transform values. **Warning:** The given sl.Orientation contains a copy of the sl.Transform values. ### `get_rotation_vector(self) -> npt.NDArray[float]` Returns the 3x1 rotation vector obtained from 3x3 rotation matrix using Rodrigues formula. :return: Rotation vector (NumPy array) created from the sl.Transform values. ### `set_rotation_vector(self, input0: float, input1: float, input2: float) -> None` Sets the rotation component of the sl.Transform with a 3x1 rotation vector (using Rodrigues' transformation). :param input0: ```rx``` component of the rotation vector. :param input1: ```ry``` component of the rotation vector. :param input2: ```rz``` component of the rotation vector. ### `get_euler_angles(self, radian=True) -> npt.NDArray[float]` Converts the rotation component of the sl.Transform into Euler angles. :param radian: Whether the angle will be returned in radian or degree. Default: True :return: Euler angles (Numpy array) created from the sl.Transform values representing the rotations around the X, Y and Z axes using YZX convention. ### `set_euler_angles(self, input0: float, input1: float, input2: float, radian=True) -> None` Sets the rotation component of the sl.Transform from Euler angles. :param input0: Roll value. :param input1: Pitch value. :param input2: Yaw value. :param radian: Whether the angle is in radian or degree. Default: True --- # Translation Class representing a translation for the positional tracking module. sl.Translation is a vector as ```[tx, ty, tz]```. You can access the data with the get() method that returns a NumPy array. ## Methods ### `__init__(self, *args, **kwargs) -> None` ### `init_translation(self, tr) -> None` Deep copy from another sl.Translation. :param tr: sl.Translation to copy. ### `init_vector(self, t1, t2, t3) -> None` Initializes the sl.Translation with its components. :param t1: First component. :param t2: Second component. :param t3: Third component. ### `normalize(self) -> None` Normalizes the current sl.Translation. ### `normalize_translation(self, tr) -> Translation` Gets the normalized sl.Translation of a given sl.Translation. :param tr: sl.Translation to be get the normalized translation from. :return: Another sl.Translation object equal to **tr.normalize(). ### `size(self) -> int` Gets the size of the sl.Translation. :return: Size of the sl.Translation. ### `dot_translation(tr1: Translation, tr2) -> float` Computes the dot product of two sl.Translation objects. :param tr1: First sl.Translation to get the dot product from. :param tr2: Sencond sl.Translation to get the dot product from. :return: Dot product of **tr1 and **tr2. ### `get(self) -> npt.NDArray[float]` Gets the sl.Translation as an NumPy array. :return: NumPy array containing the components of the sl.Translation. --- # UTM Represents a world position in UTM format. ## Properties ### `northing: double` *(read/write)* Northing coordinate. ### `UTM_zone: str` *(read/write)* UTMZone of the coordinate. ### `gamma: double` *(read/write)* Gamma coordinate. ### `easting: double` *(read/write)* Easting coordinate. ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # VoxelMeasureParameters Parameters controlling voxel decimation in Camera.retrieve_voxel_measure. ## Properties ### `centroid: bool` *(read/write)* Controls output point positions within each voxel. If True, output positions are the centroid of all points in each voxel. If False, output positions are snapped to the voxel grid center. ### `resolution_mode: VOXELIZATION_MODE` *(read/write)* How voxel size adapts with depth. See VOXELIZATION_MODE for available modes. ### `resolution_scale: float` *(read/write)* Scale factor for depth-adaptive voxel growth. Larger values produce coarser voxels at distance (fewer points, better performance). Typical range: [0.01, 1.0]. Clamped internally to [0.01, 3.0]. **Note:** Only used when resolution_mode is not VOXELIZATION_MODE.FIXED. ### `voxel_size: float` *(read/write)* Voxel grid cell size in InitParameters.coordinate_units. If <= 0, a 100 mm equivalent default is used. Clamped internally to [5 mm equivalent, max_depth_range]. ## Methods ### `__init__(self, *args, **kwargs) -> None` --- # AI_MODELS *(enum)* Lists available AI models. | Enumerator | | |:---:|:---:| | MULTI_CLASS_DETECTION | Related to sl.OBJECT_DETECTION_MODEL.MULTI_CLASS_BOX_FAST | | MULTI_CLASS_MEDIUM_DETECTION | Related to sl.OBJECT_DETECTION_MODEL.MULTI_CLASS_BOX_MEDIUM | | MULTI_CLASS_ACCURATE_DETECTION | Related to sl.OBJECT_DETECTION_MODEL.MULTI_CLASS_BOX_ACCURATE | | HUMAN_BODY_FAST_DETECTION | Related to sl.BODY_TRACKING_MODEL.HUMAN_BODY_FAST | | HUMAN_BODY_MEDIUM_DETECTION | Related to sl.BODY_TRACKING_MODEL.HUMAN_BODY_MEDIUM | | HUMAN_BODY_ACCURATE_DETECTION | Related to sl.BODY_TRACKING_MODEL.HUMAN_BODY_ACCURATE | | HUMAN_BODY_38_FAST_DETECTION | Related to sl.BODY_TRACKING_MODEL.HUMAN_BODY_FAST | | HUMAN_BODY_38_MEDIUM_DETECTION | Related to sl.BODY_TRACKING_MODEL.HUMAN_BODY_FAST | | HUMAN_BODY_38_ACCURATE_DETECTION | Related to sl.BODY_TRACKING_MODEL.HUMAN_BODY_FAST | | PERSON_HEAD_DETECTION | Related to sl.OBJECT_DETECTION_MODEL.PERSON_HEAD_BOX_FAST | | PERSON_HEAD_ACCURATE_DETECTION | Related to sl.OBJECT_DETECTION_MODEL.PERSON_HEAD_BOX_ACCURATE | | REID_ASSOCIATION | Related to sl.BatchParameters.enable | | NEURAL_LIGHT_DEPTH | Related to sl.DEPTH_MODE.NEURAL_LIGHT_DEPTH | | NEURAL_DEPTH | Related to sl.DEPTH_MODE.NEURAL | | NEURAL_PLUS_DEPTH | Related to sl.DEPTH_MODE.NEURAL_PLUS_DEPTH | ## Values - `AI_MODELS.MULTI_CLASS_DETECTION` - `AI_MODELS.MULTI_CLASS_MEDIUM_DETECTION` - `AI_MODELS.MULTI_CLASS_ACCURATE_DETECTION` - `AI_MODELS.HUMAN_BODY_FAST_DETECTION` - `AI_MODELS.HUMAN_BODY_MEDIUM_DETECTION` - `AI_MODELS.HUMAN_BODY_ACCURATE_DETECTION` - `AI_MODELS.HUMAN_BODY_38_FAST_DETECTION` - `AI_MODELS.HUMAN_BODY_38_MEDIUM_DETECTION` - `AI_MODELS.HUMAN_BODY_38_ACCURATE_DETECTION` - `AI_MODELS.PERSON_HEAD_DETECTION` - `AI_MODELS.PERSON_HEAD_ACCURATE_DETECTION` - `AI_MODELS.REID_ASSOCIATION` - `AI_MODELS.NEURAL_LIGHT_DEPTH` - `AI_MODELS.NEURAL_DEPTH` - `AI_MODELS.NEURAL_PLUS_DEPTH` - `AI_MODELS.LAST` --- # AREA_EXPORTING_STATE *(enum)* Lists the different states of spatial memory area export. | Enumerator | | |:---:|:---:| | SUCCESS | The spatial memory file has been successfully created. | | RUNNING | The spatial memory is currently being written. | | NOT_STARTED | The spatial memory file exportation has not been called. | | FILE_EMPTY | The spatial memory contains no data, the file is empty. | | FILE_ERROR | The spatial memory file has not been written because of a wrong file name. | | SPATIAL_MEMORY_DISABLED | The spatial memory learning is disabled. No file can be created. | ## Values - `AREA_EXPORTING_STATE.SUCCESS` - `AREA_EXPORTING_STATE.RUNNING` - `AREA_EXPORTING_STATE.NOT_STARTED` - `AREA_EXPORTING_STATE.FILE_EMPTY` - `AREA_EXPORTING_STATE.FILE_ERROR` - `AREA_EXPORTING_STATE.SPATIAL_MEMORY_DISABLED` - `AREA_EXPORTING_STATE.LAST` --- # BODY_18_PARTS *(enum)* Semantic of human body parts and order of sl.BodyData.keypoint for sl.BODY_FORMAT.BODY_18. | BODY_18_PARTS | Keypoint number | |:---:|:---:| | NOSE | 0 | | NECK | 1 | | RIGHT_SHOULDER | 2 | | RIGHT_ELBOW | 3 | | RIGHT_WRIST | 4 | | LEFT_SHOULDER | 5 | | LEFT_ELBOW | 6 | | LEFT_WRIST | 7 | | RIGHT_HIP | 8 | | RIGHT_KNEE | 9 | | RIGHT_ANKLE | 10 | | LEFT_HIP | 11 | | LEFT_KNEE | 12 | | LEFT_ANKLE | 13 | | RIGHT_EYE | 14 | | LEFT_EYE | 15 | | RIGHT_EAR | 16 | | LEFT_EAR | 17 | ## Values - `BODY_18_PARTS.NOSE` - `BODY_18_PARTS.NECK` - `BODY_18_PARTS.RIGHT_SHOULDER` - `BODY_18_PARTS.RIGHT_ELBOW` - `BODY_18_PARTS.RIGHT_WRIST` - `BODY_18_PARTS.LEFT_SHOULDER` - `BODY_18_PARTS.LEFT_ELBOW` - `BODY_18_PARTS.LEFT_WRIST` - `BODY_18_PARTS.RIGHT_HIP` - `BODY_18_PARTS.RIGHT_KNEE` - `BODY_18_PARTS.RIGHT_ANKLE` - `BODY_18_PARTS.LEFT_HIP` - `BODY_18_PARTS.LEFT_KNEE` - `BODY_18_PARTS.LEFT_ANKLE` - `BODY_18_PARTS.RIGHT_EYE` - `BODY_18_PARTS.LEFT_EYE` - `BODY_18_PARTS.RIGHT_EAR` - `BODY_18_PARTS.LEFT_EAR` - `BODY_18_PARTS.LAST` --- # BODY_34_PARTS *(enum)* Semantic of human body parts and order of sl.BodyData.keypoint for sl.BODY_FORMAT.BODY_34. | BODY_34_PARTS | Keypoint number | |:---:|:---:| | PELVIS | 0 | | NAVAL_SPINE | 1 | | CHEST_SPINE | 2 | | NECK | 3 | | LEFT_CLAVICLE | 4 | | LEFT_SHOULDER | 5 | | LEFT_ELBOW | 6 | | LEFT_WRIST | 7 | | LEFT_HAND | 8 | | LEFT_HANDTIP | 9 | | LEFT_THUMB | 10 | | RIGHT_CLAVICLE | 11 | | RIGHT_SHOULDER | 12 | | RIGHT_ELBOW | 13 | | RIGHT_WRIST | 14 | | RIGHT_HAND | 15 | | RIGHT_HANDTIP | 16 | | RIGHT_THUMB | 17 | | LEFT_HIP | 18 | | LEFT_KNEE | 19 | | LEFT_ANKLE | 20 | | LEFT_FOOT | 21 | | RIGHT_HIP | 22 | | RIGHT_KNEE | 23 | | RIGHT_ANKLE | 24 | | RIGHT_FOOT | 25 | | HEAD | 26 | | NOSE | 27 | | LEFT_EYE | 28 | | LEFT_EAR | 29 | | RIGHT_EYE | 30 | | RIGHT_EAR | 31 | | LEFT_HEEL | 32 | | RIGHT_HEEL | 33 | ## Values - `BODY_34_PARTS.PELVIS` - `BODY_34_PARTS.NAVAL_SPINE` - `BODY_34_PARTS.CHEST_SPINE` - `BODY_34_PARTS.NECK` - `BODY_34_PARTS.LEFT_CLAVICLE` - `BODY_34_PARTS.LEFT_SHOULDER` - `BODY_34_PARTS.LEFT_ELBOW` - `BODY_34_PARTS.LEFT_WRIST` - `BODY_34_PARTS.LEFT_HAND` - `BODY_34_PARTS.LEFT_HANDTIP` - `BODY_34_PARTS.LEFT_THUMB` - `BODY_34_PARTS.RIGHT_CLAVICLE` - `BODY_34_PARTS.RIGHT_SHOULDER` - `BODY_34_PARTS.RIGHT_ELBOW` - `BODY_34_PARTS.RIGHT_WRIST` - `BODY_34_PARTS.RIGHT_HAND` - `BODY_34_PARTS.RIGHT_HANDTIP` - `BODY_34_PARTS.RIGHT_THUMB` - `BODY_34_PARTS.LEFT_HIP` - `BODY_34_PARTS.LEFT_KNEE` - `BODY_34_PARTS.LEFT_ANKLE` - `BODY_34_PARTS.LEFT_FOOT` - `BODY_34_PARTS.RIGHT_HIP` - `BODY_34_PARTS.RIGHT_KNEE` - `BODY_34_PARTS.RIGHT_ANKLE` - `BODY_34_PARTS.RIGHT_FOOT` - `BODY_34_PARTS.HEAD` - `BODY_34_PARTS.NOSE` - `BODY_34_PARTS.LEFT_EYE` - `BODY_34_PARTS.LEFT_EAR` - `BODY_34_PARTS.RIGHT_EYE` - `BODY_34_PARTS.RIGHT_EAR` - `BODY_34_PARTS.LEFT_HEEL` - `BODY_34_PARTS.RIGHT_HEEL` - `BODY_34_PARTS.LAST` --- # BODY_38_PARTS *(enum)* Semantic of human body parts and order of sl.BodyData.keypoint for sl.BODY_FORMAT.BODY_38. | BODY_38_PARTS | Keypoint number | |:---:|:---:| | PELVIS | 0 | | SPINE_1 | 1 | | SPINE_2 | 2 | | SPINE_3 | 3 | | NECK | 4 | | NOSE | 5 | | LEFT_EYE | 6 | | RIGHT_EYE | 7 | | LEFT_EAR | 8 | | RIGHT_EAR | 9 | | LEFT_CLAVICLE | 10 | | RIGHT_CLAVICLE | 11 | | LEFT_SHOULDER | 12 | | RIGHT_SHOULDER | 13 | | LEFT_ELBOW | 14 | | RIGHT_ELBOW | 15 | | LEFT_WRIST | 16 | | RIGHT_WRIST | 17 | | LEFT_HIP | 18 | | RIGHT_HIP | 19 | | LEFT_KNEE | 20 | | RIGHT_KNEE | 21 | | LEFT_ANKLE | 22 | | RIGHT_ANKLE | 23 | | LEFT_BIG_TOE | 24 | | RIGHT_BIG_TOE | 25 | | LEFT_SMALL_TOE | 26 | | RIGHT_SMALL_TOE | 27 | | LEFT_HEEL | 28 | | RIGHT_HEEL | 29 | | LEFT_HAND_THUMB_4 | 30 | | RIGHT_HAND_THUMB_4 | 31 | | LEFT_HAND_INDEX_1 | 32 | | RIGHT_HAND_INDEX_1 | 33 | | LEFT_HAND_MIDDLE_4 | 34 | | RIGHT_HAND_MIDDLE_4 | 35 | | LEFT_HAND_PINKY_1 | 36 | | RIGHT_HAND_PINKY_1 | 37 | ## Values - `BODY_38_PARTS.PELVIS` - `BODY_38_PARTS.SPINE_1` - `BODY_38_PARTS.SPINE_2` - `BODY_38_PARTS.SPINE_3` - `BODY_38_PARTS.NECK` - `BODY_38_PARTS.NOSE` - `BODY_38_PARTS.LEFT_EYE` - `BODY_38_PARTS.RIGHT_EYE` - `BODY_38_PARTS.LEFT_EAR` - `BODY_38_PARTS.RIGHT_EAR` - `BODY_38_PARTS.LEFT_CLAVICLE` - `BODY_38_PARTS.RIGHT_CLAVICLE` - `BODY_38_PARTS.LEFT_SHOULDER` - `BODY_38_PARTS.RIGHT_SHOULDER` - `BODY_38_PARTS.LEFT_ELBOW` - `BODY_38_PARTS.RIGHT_ELBOW` - `BODY_38_PARTS.LEFT_WRIST` - `BODY_38_PARTS.RIGHT_WRIST` - `BODY_38_PARTS.LEFT_HIP` - `BODY_38_PARTS.RIGHT_HIP` - `BODY_38_PARTS.LEFT_KNEE` - `BODY_38_PARTS.RIGHT_KNEE` - `BODY_38_PARTS.LEFT_ANKLE` - `BODY_38_PARTS.RIGHT_ANKLE` - `BODY_38_PARTS.LEFT_BIG_TOE` - `BODY_38_PARTS.RIGHT_BIG_TOE` - `BODY_38_PARTS.LEFT_SMALL_TOE` - `BODY_38_PARTS.RIGHT_SMALL_TOE` - `BODY_38_PARTS.LEFT_HEEL` - `BODY_38_PARTS.RIGHT_HEEL` - `BODY_38_PARTS.LEFT_HAND_THUMB_4` - `BODY_38_PARTS.RIGHT_HAND_THUMB_4` - `BODY_38_PARTS.LEFT_HAND_INDEX_1` - `BODY_38_PARTS.RIGHT_HAND_INDEX_1` - `BODY_38_PARTS.LEFT_HAND_MIDDLE_4` - `BODY_38_PARTS.RIGHT_HAND_MIDDLE_4` - `BODY_38_PARTS.LEFT_HAND_PINKY_1` - `BODY_38_PARTS.RIGHT_HAND_PINKY_1` - `BODY_38_PARTS.LAST` --- # BODY_FORMAT *(enum)* Lists supported skeleton body models. | Enumerator | | |:---:|:---:| | BODY_18 | 18-keypoint model Basic body model | | BODY_34 | 34-keypoint model Note: Requires body fitting enabled. | | BODY_38 | 38-keypoint model Including simplified face, hands and feet.Note: Early Access | ## Values - `BODY_FORMAT.BODY_18` - `BODY_FORMAT.BODY_34` - `BODY_FORMAT.BODY_38` - `BODY_FORMAT.LAST` --- # BODY_KEYPOINTS_SELECTION *(enum)* Lists supported models for skeleton keypoints selection. | Enumerator | | |:---:|:---:| | FULL | Full keypoint model | | UPPER_BODY | Upper body keypoint model Will output only upper body (from hip). | ## Values - `BODY_KEYPOINTS_SELECTION.FULL` - `BODY_KEYPOINTS_SELECTION.UPPER_BODY` - `BODY_KEYPOINTS_SELECTION.LAST` --- # BODY_TRACKING_MODEL *(enum)* Lists available models for the body tracking module. | Enumerator | | |:---:|:---:| | HUMAN_BODY_FAST | Keypoints based, specific to human skeleton, real time performance even on Jetson or low end GPU cards. | | HUMAN_BODY_ACCURATE | Keypoints based, specific to human skeleton, state of the art accuracy, requires powerful GPU. | | HUMAN_BODY_MEDIUM | Keypoints based, specific to human skeleton, compromise between accuracy and speed. | ## Values - `BODY_TRACKING_MODEL.HUMAN_BODY_FAST` - `BODY_TRACKING_MODEL.HUMAN_BODY_ACCURATE` - `BODY_TRACKING_MODEL.HUMAN_BODY_MEDIUM` - `BODY_TRACKING_MODEL.LAST` --- # BUS_TYPE *(enum)* Lists available LIVE input type in the ZED SDK. | Enumerator | | |:---:|:---:| | USB | USB input mode | | GMSL | GMSL input mode Note: Only on NVIDIA Jetson. | | AUTO | Automatically select the input type. Trying first for available USB cameras, then GMSL. | ## Values - `BUS_TYPE.USB` - `BUS_TYPE.GMSL` - `BUS_TYPE.AUTO` - `BUS_TYPE.LAST` --- # CAMERA_MOTION_STATE *(enum)* Lists different states of the camera motion. | Enumerator | | |:---:|:---:| | STATIC | The camera is static. | | MOVING | The camera is moving. | | FALLING | The camera is falling. | ## Values - `CAMERA_MOTION_STATE.STATIC` - `CAMERA_MOTION_STATE.MOVING` - `CAMERA_MOTION_STATE.FALLING` - `CAMERA_MOTION_STATE.LAST` --- # CAMERA_STATE *(enum)* Lists possible camera states. | Enumerator | | |:---:|:---:| | AVAILABLE | The camera can be opened by the ZED SDK. | | NOT_AVAILABLE | The camera is already opened and unavailable. | ## Values - `CAMERA_STATE.AVAILABLE` - `CAMERA_STATE.NOT_AVAILABLE` - `CAMERA_STATE.LAST` --- # COMM_TYPE *(enum)* Lists the different types of communications available for Fusion module. | Enumerator | | |:---:|:---:| | LOCAL_NETWORK | The sender and receiver are on the same local network and communicate by RTP. The communication can be affected by the local network load. | | INTRA_PROCESS | Both sender and receiver are declared by the same process and can be in different threads. This type of communication is optimized. | ## Values - `COMM_TYPE.LOCAL_NETWORK` - `COMM_TYPE.INTRA_PROCESS` - `COMM_TYPE.LAST` --- # COORDINATE_SYSTEM *(enum)* Lists available coordinates systems for positional tracking and 3D measures. | Enumerator | | |:---:|:---:| | IMAGE | Standard coordinates system in computer vision. Used in OpenCV: see `here `_. | | LEFT_HANDED_Y_UP | Left-handed with Y up and Z forward. Used in Unity with DirectX. | | RIGHT_HANDED_Y_UP | Right-handed with Y pointing up and Z backward. Used in OpenGL. | | RIGHT_HANDED_Z_UP | Right-handed with Z pointing up and Y forward. Used in 3DSMax. | | LEFT_HANDED_Z_UP | Left-handed with Z axis pointing up and X forward. Used in Unreal Engine. | | RIGHT_HANDED_Z_UP_X_FWD | Right-handed with Z pointing up and X forward. Used in ROS (REP 103). | ## Values - `COORDINATE_SYSTEM.IMAGE` - `COORDINATE_SYSTEM.LEFT_HANDED_Y_UP` - `COORDINATE_SYSTEM.RIGHT_HANDED_Y_UP` - `COORDINATE_SYSTEM.RIGHT_HANDED_Z_UP` - `COORDINATE_SYSTEM.LEFT_HANDED_Z_UP` - `COORDINATE_SYSTEM.RIGHT_HANDED_Z_UP_X_FWD` - `COORDINATE_SYSTEM.LAST` --- # COPY_TYPE *(enum)* Lists available copy operation on sl.Mat. **Note:** The ZED SDK Python wrapper does not support GPU data storage/access. | Enumerator | | |:---:|:---:| | CPU_CPU | Copy data from CPU to CPU. | | GPU_CPU | Copy data from GPU to CPU. | | CPU_GPU | Copy data from CPU to GPU. | | GPU_GPU | Copy data from GPU to GPU. | ## Values - `COPY_TYPE.CPU_CPU` - `COPY_TYPE.GPU_CPU` - `COPY_TYPE.CPU_GPU` - `COPY_TYPE.GPU_GPU` --- # DEPTH_MODE *(enum)* Lists available depth computation modes. | Enumerator | | |:---:|:---:| | NONE | No depth map computation. Only rectified stereo images will be available. | | PERFORMANCE | Computation mode optimized for speed. | | QUALITY | Computation mode designed for challenging areas with untextured surfaces. | | ULTRA | Computation mode that favors edges and sharpness. Requires more GPU memory and computation power. | | NEURAL_LIGHT | End to End Neural disparity estimation. Requires AI module. | | NEURAL | End to End Neural disparity estimation. Requires AI module. | | NEURAL_PLUS | End to End Neural disparity estimation. More precise but requires more GPU memory and computation power. Requires AI module. | ## Values - `DEPTH_MODE.NONE` - `DEPTH_MODE.PERFORMANCE` - `DEPTH_MODE.QUALITY` - `DEPTH_MODE.ULTRA` - `DEPTH_MODE.NEURAL_LIGHT` - `DEPTH_MODE.NEURAL` - `DEPTH_MODE.NEURAL_PLUS` - `DEPTH_MODE.LAST` --- # FLIP_MODE *(enum)* Lists possible flip modes of the camera. | Enumerator | | |:---:|:---:| | OFF | No flip applied. Default behavior. | | ON | Images and camera sensors' data are flipped useful when your camera is mounted upside down. | | AUTO | In LIVE mode, use the camera orientation (if an IMU is available) to set the flip mode. In SVO mode, read the state of this enum when recorded. | ## Values - `FLIP_MODE.OFF` - `FLIP_MODE.ON` - `FLIP_MODE.AUTO` --- # FUSION_ERROR_CODE *(enum)* Lists the types of error that can be raised by the Fusion. | Enumerator | | |:---:|:---:| | GNSS_DATA_NEED_FIX | GNSS Data need fix status in order to run fusion. | | GNSS_DATA_COVARIANCE_MUST_VARY | Ingested covariance data must vary between ingest. | | BODY_FORMAT_MISMATCH | The senders are using different body formats. Consider changing them. | | NOT_ENABLED | The following module was not enabled. | | SOURCE_MISMATCH | Some sources are provided by SVO and others by LIVE stream. | | CONNECTION_TIMED_OUT | Connection timed out. Unable to reach the sender. Verify the sender's IP/port. | | SHARED_MEMORY_LEAK | Intra-process shared memory allocation issue. Multiple connections to the same data. | | INVALID_IP_ADDRESS | The provided IP address format is incorrect. Please provide the IP in the format 'a.b.c.d', where (a, b, c, d) are numbers between 0 and 255. | | CONNECTION_ERROR | Something goes bad in the connection between sender and receiver. | | FAILURE | Standard code for unsuccessful behavior. | | SUCCESS | Standard code for successful behavior. | | FUSION_INCONSISTENT_FPS | Significant differences observed between sender's FPS. | | FUSION_FPS_TOO_LOW | At least one sender has an FPS lower than 10 FPS. | | INVALID_TIMESTAMP | Problem detected with the ingested timestamp. Sample data will be ignored. | | INVALID_COVARIANCE | Problem detected with the ingested covariance. Sample data will be ignored. | | NO_NEW_DATA_AVAILABLE | All data from all sources has been consumed. No new data is available for processing. | ## Values - `FUSION_ERROR_CODE.GNSS_DATA_NEED_FIX` - `FUSION_ERROR_CODE.GNSS_DATA_COVARIANCE_MUST_VARY` - `FUSION_ERROR_CODE.BODY_FORMAT_MISMATCH` - `FUSION_ERROR_CODE.MODULE_NOT_ENABLED` - `FUSION_ERROR_CODE.SOURCE_MISMATCH` - `FUSION_ERROR_CODE.CONNECTION_TIMED_OUT` - `FUSION_ERROR_CODE.MEMORY_ALREADY_USED` - `FUSION_ERROR_CODE.INVALID_IP_ADDRESS` - `FUSION_ERROR_CODE.FAILURE` - `FUSION_ERROR_CODE.SUCCESS` - `FUSION_ERROR_CODE.FUSION_INCONSISTENT_FPS` - `FUSION_ERROR_CODE.FUSION_FPS_TOO_LOW` - `FUSION_ERROR_CODE.INVALID_TIMESTAMP` - `FUSION_ERROR_CODE.INVALID_COVARIANCE` - `FUSION_ERROR_CODE.NO_NEW_DATA_AVAILABLE` --- # FUSION_REFERENCE_FRAME *(enum)* Enum to define the reference frame of the fusion SDK. | Enumerator | | |:---:|:---:| | WORLD | The world frame is the reference frame of the world according to the fused positional Tracking. | | BASELINK | The base link frame is the reference frame where camera calibration is given. | ## Values - `FUSION_REFERENCE_FRAME.WORLD` - `FUSION_REFERENCE_FRAME.BASELINK` --- # GNSS_FUSION_STATUS *(enum)* Lists that represents the current GNSS fusion status | Enumerator | | |:---:|:---:| | OK | The GNSS fusion module is calibrated and working successfully. | | OFF | The GNSS fusion module is not enabled. | | CALIBRATION_IN_PROGRESS | Calibration of the GNSS/VIO fusion module is in progress. | | RECALIBRATION_IN_PROGRESS | Re-alignment of GNSS/VIO data is in progress, leading to potentially inaccurate global position. | ## Values - `GNSS_FUSION_STATUS.OK` - `GNSS_FUSION_STATUS.OFF` - `GNSS_FUSION_STATUS.CALIBRATION_IN_PROGRESS` - `GNSS_FUSION_STATUS.RECALIBRATION_IN_PROGRESS` - `GNSS_FUSION_STATUS.LAST` --- # GNSS_MODE *(enum)* Lists that represents the mode of GNSS signal. | Enumerator | | |:---:|:---:| | UNKNOWN | No GNSS fix data is available. | | NO_FIX | No GNSS fix is available. | | FIX_2D | 2D GNSS fix, providing latitude and longitude coordinates but without altitude information. | | FIX_3D | 3D GNSS fix, providing latitude, longitude, and altitude coordinates. | ## Values - `GNSS_MODE.UNKNOWN` - `GNSS_MODE.NO_FIX` - `GNSS_MODE.FIX_2D` - `GNSS_MODE.FIX_3D` - `GNSS_MODE.LAST` --- # GNSS_STATUS *(enum)* Lists that represents the status of the of GNSS signal. | Enumerator | | |:---:|:---:| | UNKNOWN | No GNSS fix data is available. | | SINGLE | Single Point Positioning. | | DGNSS | Differential GNSS. | | PPS | Precise Positioning Service. | | RTK_FLOAT | Real Time Kinematic Float. | | RTK_FIX | Real Time Kinematic Fixed. | ## Values - `GNSS_STATUS.UNKNOWN` - `GNSS_STATUS.SINGLE` - `GNSS_STATUS.DGNSS` - `GNSS_STATUS.PPS` - `GNSS_STATUS.RTK_FLOAT` - `GNSS_STATUS.RTK_FIX` - `GNSS_STATUS.LAST` --- # HEADING_STATE *(enum)* Lists the different states of the magnetic heading. | Enumerator | | |:---:|:---:| | GOOD | The heading is reliable and not affected by iron interferences. | | OK | The heading is reliable, but affected by slight iron interferences. | | NOT_GOOD | The heading is not reliable because affected by strong iron interferences. | | NOT_CALIBRATED | The magnetometer has not been calibrated. | | MAG_NOT_AVAILABLE | The magnetometer sensor is not available. | ## Values - `HEADING_STATE.GOOD` - `HEADING_STATE.OK` - `HEADING_STATE.NOT_GOOD` - `HEADING_STATE.NOT_CALIBRATED` - `HEADING_STATE.MAG_NOT_AVAILABLE` - `HEADING_STATE.LAST` --- # INFERENCE_PRECISION *(enum)* Report the actual inference precision used | Enumerator | | |:---:|:---:| | FP32 | | | FP16 | | | INT8 | | ## Values - `INFERENCE_PRECISION.FP32` - `INFERENCE_PRECISION.FP16` - `INFERENCE_PRECISION.INT8` - `INFERENCE_PRECISION.LAST` --- # INPUT_TYPE *(enum)* Lists available input types in the ZED SDK. | Enumerator | | |:---:|:---:| | USB | USB input mode | | SVO | SVO file input mode | | STREAM | STREAM input mode (requires to use Camera.enable_streaming "enable_streaming()" / Camera.disable_streaming "disable_streaming()" on the "sender" side) | | GMSL | GMSL input mode (only on NVIDIA Jetson) | ## Values - `INPUT_TYPE.USB` - `INPUT_TYPE.SVO` - `INPUT_TYPE.STREAM` - `INPUT_TYPE.GMSL` - `INPUT_TYPE.LAST` --- # LIDAR_MEASURE *(enum)* Lists available Lidar measures (point clouds, range maps, etc.) ## Values - `LIDAR_MEASURE.RANGE` - `LIDAR_MEASURE.RANGE2` - `LIDAR_MEASURE.SIGNAL` - `LIDAR_MEASURE.SIGNAL2` - `LIDAR_MEASURE.INTENSITY` - `LIDAR_MEASURE.REFLECTIVITY` - `LIDAR_MEASURE.REFLECTIVITY2` - `LIDAR_MEASURE.NEAR_IR` - `LIDAR_MEASURE.XYZ` - `LIDAR_MEASURE.XYZ_RANGE` - `LIDAR_MEASURE.XYZ_RANGE2` - `LIDAR_MEASURE.XYZ_SIGNAL` - `LIDAR_MEASURE.XYZ_SIGNAL2` - `LIDAR_MEASURE.XYZ_INTENSITY` - `LIDAR_MEASURE.XYZ_REFLECTIVITY` - `LIDAR_MEASURE.XYZ_REFLECTIVITY2` - `LIDAR_MEASURE.XYZ_NEAR_IR` - `LIDAR_MEASURE.XYZ_RANGE_VIEW` - `LIDAR_MEASURE.XYZ_RANGE2_VIEW` - `LIDAR_MEASURE.XYZ_SIGNAL_VIEW` - `LIDAR_MEASURE.XYZ_SIGNAL2_VIEW` - `LIDAR_MEASURE.XYZ_INTENSITY_VIEW` - `LIDAR_MEASURE.XYZ_REFLECTIVITY_VIEW` - `LIDAR_MEASURE.XYZ_REFLECTIVITY2_VIEW` - `LIDAR_MEASURE.XYZ_NEAR_IR_VIEW` - `LIDAR_MEASURE.RANGE_RAW` - `LIDAR_MEASURE.RANGE2_RAW` - `LIDAR_MEASURE.SIGNAL_RAW` - `LIDAR_MEASURE.SIGNAL2_RAW` - `LIDAR_MEASURE.REFLECTIVITY_RAW` - `LIDAR_MEASURE.REFLECTIVITY2_RAW` - `LIDAR_MEASURE.NEAR_IR_RAW` --- # LIDAR_MODE *(enum)* Lists available Lidar modes (resolution and frequency). | Enumerator | Description | |:---:|:---:| | AUTO | If used, will not change the existing config. | | MODE_512x10 | 512 points per rotation at 10Hz. | | MODE_1024x10 | 1024 points per rotation at 10Hz. | | MODE_2048x10 | 2048 points per rotation at 10Hz. | | MODE_512x20 | 512 points per rotation at 20Hz. | | MODE_1024x20 | 1024 points per rotation at 20Hz. | ## Values - `LIDAR_MODE.AUTO` - `LIDAR_MODE.MODE_512x10` - `LIDAR_MODE.MODE_1024x10` - `LIDAR_MODE.MODE_2048x10` - `LIDAR_MODE.MODE_512x20` - `LIDAR_MODE.MODE_1024x20` --- # LIDAR_MULTICAST_MODE *(enum)* Lists available multicast modes for Lidar. | Enumerator | Description | |:---:|:---:| | OFF | Force unicast mode. Reconfigures sensor if needed. | | AUTO | Smart detection: joins existing multicast passively, stays unicast if alone. | | ON | Force multicast mode. Uses provided IP or auto-selects 239.201.201.201. | ## Values - `LIDAR_MULTICAST_MODE.OFF` - `LIDAR_MULTICAST_MODE.AUTO` - `LIDAR_MULTICAST_MODE.ON` --- # LIDAR_VIEW *(enum)* Lists available Lidar view types for visualization. ## Values - `LIDAR_VIEW.INTENSITY` - `LIDAR_VIEW.REFLECTIVITY` - `LIDAR_VIEW.DEPTH` - `LIDAR_VIEW.RANGE` - `LIDAR_VIEW.SIGNAL` - `LIDAR_VIEW.NEAR_IR` - `LIDAR_VIEW.RANGE2` - `LIDAR_VIEW.SIGNAL2` - `LIDAR_VIEW.REFLECTIVITY2` --- # MAPPING_RANGE *(enum)* Lists the spatial mapping depth range presets. | Enumerator | | |:---:|:---:| | SHORT | Only depth close to the camera will be used during spatial mapping. | | MEDIUM | Medium depth range. | | LONG | Takes into account objects that are far. Useful for outdoor purposes. | | AUTO | Depth range will be computed based on current sl.Camera state and parameters. | ## Values - `MAPPING_RANGE.SHORT` - `MAPPING_RANGE.MEDIUM` - `MAPPING_RANGE.LONG` - `MAPPING_RANGE.AUTO` --- # MAPPING_RESOLUTION *(enum)* Lists the spatial mapping resolution presets. | Enumerator | | |:---:|:---:| | HIGH | Creates a detailed geometry. Requires lots of memory. | | MEDIUM | Small variations in the geometry will disappear. Useful for big objects. | | LOW | Keeps only huge variations of the geometry. Useful for outdoor purposes. | ## Values - `MAPPING_RESOLUTION.HIGH` - `MAPPING_RESOLUTION.MEDIUM` - `MAPPING_RESOLUTION.LOW` --- # MAT_TYPE *(enum)* Lists available sl.Mat formats. **Note:** sl.Mat type depends on image or measure type. **Note:** For the dependencies, see sl.VIEW and sl.MEASURE. | Enumerator | | |:---:|:---:| | F32_C1 | 1-channel matrix of float | | F32_C2 | 2-channel matrix of float | | F32_C3 | 3-channel matrix of float | | F32_C4 | 4-channel matrix of float | | U8_C1 | 1-channel matrix of unsigned char | | U8_C2 | 2-channel matrix of unsigned char | | U8_C3 | 3-channel matrix of unsigned char | | U8_C4 | 4-channel matrix of unsigned char | | U16_C1 | 1-channel matrix of unsigned short | | S8_C4 | 4-channel matrix of signed char | | NV12 | YUV 4:2:0 semi-planar data Y UVUVUV | ## Values - `MAT_TYPE.F32_C1` - `MAT_TYPE.F32_C2` - `MAT_TYPE.F32_C3` - `MAT_TYPE.F32_C4` - `MAT_TYPE.U8_C1` - `MAT_TYPE.U8_C2` - `MAT_TYPE.U8_C3` - `MAT_TYPE.U8_C4` - `MAT_TYPE.U16_C1` - `MAT_TYPE.S8_C4` - `MAT_TYPE.NV12` --- # MEASURE *(enum)* Lists retrievable measures. | Enumerator | | |:---:|:---:| | DISPARITY | Disparity map. Each pixel contains 1 float. Type: sl.MAT_TYPE.F32_C1 | | DEPTH | Depth map in sl.UNIT defined in sl.InitParameters.coordinate_units. Each pixel contains 1 float. Type: sl.MAT_TYPE.F32_C1 | | CONFIDENCE | Certainty/confidence of the depth map. Each pixel contains 1 float. Type: sl.MAT_TYPE.F32_C1 | | XYZ | Point cloud. Each pixel contains 4 float (X, Y, Z, not used). Type: sl.MAT_TYPE.F32_C4 | | XYZRGBA | Colored point cloud. Each pixel contains 4 float (X, Y, Z, color). The color should to be read as an unsigned char[4] representing the RGBA color. Type: sl.MAT_TYPE.F32_C4 | | XYZBGRA | Colored point cloud. Each pixel contains 4 float (X, Y, Z, color). The color should to be read as an unsigned char[4] representing the BGRA color. Type: sl.MAT_TYPE.F32_C4 | | XYZARGB | Colored point cloud. Each pixel contains 4 float (X, Y, Z, color). The color should to be read as an unsigned char[4] representing the ARGB color. Type: sl.MAT_TYPE.F32_C4 | | XYZABGR | Colored point cloud. Each pixel contains 4 float (X, Y, Z, color). The color should to be read as an unsigned char[4] representing the ABGR color. Type: sl.MAT_TYPE.F32_C4 | | NORMALS | Normal vectors map. Each pixel contains 4 float (X, Y, Z, 0). Type: sl.MAT_TYPE.F32_C4 | | DISPARITY_RIGHT | Disparity map for right sensor. Each pixel contains 1 float. Type: sl.MAT_TYPE.F32_C1 | | DEPTH_RIGHT | Depth map for right sensor. Each pixel contains 1 float. Type: sl.MAT_TYPE.F32_C1 | | XYZ_RIGHT | Point cloud for right sensor. Each pixel contains 4 float (X, Y, Z, not used). Type: sl.MAT_TYPE.F32_C4 | | XYZRGBA_RIGHT | Colored point cloud for right sensor. Each pixel contains 4 float (X, Y, Z, color). The color needs to be read as an unsigned char[4] representing the RGBA color. Type: sl.MAT_TYPE.F32_C4 | | XYZBGRA_RIGHT | Colored point cloud for right sensor. Each pixel contains 4 float (X, Y, Z, color). The color needs to be read as an unsigned char[4] representing the BGRA color. Type: sl.MAT_TYPE.F32_C4 | | XYZARGB_RIGHT | Colored point cloud for right sensor. Each pixel contains 4 float (X, Y, Z, color). The color needs to be read as an unsigned char[4] representing the ARGB color. Type: sl.MAT_TYPE.F32_C4 | | XYZABGR_RIGHT | Colored point cloud for right sensor. Each pixel contains 4 float (X, Y, Z, color). The color needs to be read as an unsigned char[4] representing the ABGR color. Type: sl.MAT_TYPE.F32_C4 | | NORMALS_RIGHT | Normal vectors map for right view. Each pixel contains 4 float (X, Y, Z, 0). Type: sl.MAT_TYPE.F32_C4 | | DEPTH_U16_MM | Depth map in millimeter whatever the sl.UNIT defined in sl.InitParameters.coordinate_units. Invalid values are set to 0 and depth values are clamped at 65000. Each pixel contains 1 unsigned short. Type: sl.MAT_TYPE.U16_C1 | | DEPTH_U16_MM_RIGHT | Depth map in millimeter for right sensor. Each pixel contains 1 unsigned short. Type: sl.MAT_TYPE.U16_C1 | ## Values - `MEASURE.DISPARITY` - `MEASURE.DEPTH` - `MEASURE.CONFIDENCE` - `MEASURE.XYZ` - `MEASURE.XYZRGBA` - `MEASURE.XYZBGRA` - `MEASURE.XYZARGB` - `MEASURE.XYZABGR` - `MEASURE.NORMALS` - `MEASURE.DISPARITY_RIGHT` - `MEASURE.DEPTH_RIGHT` - `MEASURE.XYZ_RIGHT` - `MEASURE.XYZRGBA_RIGHT` - `MEASURE.XYZBGRA_RIGHT` - `MEASURE.XYZARGB_RIGHT` - `MEASURE.XYZABGR_RIGHT` - `MEASURE.NORMALS_RIGHT` - `MEASURE.DEPTH_U16_MM` - `MEASURE.DEPTH_U16_MM_RIGHT` - `MEASURE.LAST` --- # MEM *(enum)* Lists available memory type. **Note:** The ZED SDK Python wrapper does not support GPU data storage/access. | Enumerator | | |:---:|:---:| | CPU | Data will be stored on the CPU (processor side). | | GPU | Data will be stored on the GPU | | BOTH | Data will be stored on both the CPU and GPU memory | ## Values - `MEM.CPU` - `MEM.GPU` - `MEM.BOTH` --- # MESH_CREATION *(enum)* Class representing a fused point cloud and containing the geometric and color data of the scene captured by the spatial mapping module. By default the fused point cloud is defined as a set of point cloud chunks. This way we update only the required data, avoiding a time consuming remapping process every time a small part of the sl.FusedPointCloud cloud is changed. ## Values - `MESH_CREATION.NONE` - `MESH_CREATION.LIVE` - `MESH_CREATION.LOAD` --- # MESH_FILE_FORMAT *(enum)* Lists available mesh file formats. | Enumerator | | |:---:|:---:| | PLY | Contains only vertices and faces. | | PLY_BIN | Contains only vertices and faces encoded in binary. | | OBJ | Contains vertices, normals, faces, and texture information (if possible). | ## Values - `MESH_FILE_FORMAT.PLY` - `MESH_FILE_FORMAT.PLY_BIN` - `MESH_FILE_FORMAT.OBJ` - `MESH_FILE_FORMAT.LAST` --- # MESH_FILTER *(enum)* Lists available mesh filtering intensities. | Enumerator | | |:---:|:---:| | LOW | Clean the mesh by closing small holes and removing isolated faces. | | MEDIUM | Soft faces decimation and smoothing. | | HIGH | Drastically reduce the number of faces and apply a soft smooth. | ## Values - `MESH_FILTER.LOW` - `MESH_FILTER.MEDIUM` - `MESH_FILTER.HIGH` --- # MESH_TEXTURE_FORMAT *(enum)* Lists available mesh texture formats. | Enumerator | | |:---:|:---:| | RGB | The texture will be on 3 channels. | | RGBA | The texture will be on 4 channels. | ## Values - `MESH_TEXTURE_FORMAT.RGB` - `MESH_TEXTURE_FORMAT.RGBA` - `MESH_TEXTURE_FORMAT.LAST` --- # MODEL *(enum)* Lists ZED camera model. | Enumerator | | |:---:|:---:| | ZED | ZED camera model | | ZED_M | ZED Mini (ZED M) camera model | | ZED2 | ZED 2 camera model | | ZED2i | ZED 2i camera model | | ZED_X | ZED X camera model | | ZED_XM | ZED X Mini (ZED XM) camera model | | ZED_X_NANO | ZED X Nano camera model | | ZED_X_HDR | ZED X HDR camera model | | ZED_X_HDR_MINI | ZED X HDR Mini camera model | | ZED_X_HDR_MAX | ZED X HDR Wide camera model | | VIRTUAL_ZED_X | Virtual ZED X generated from 2 ZED X One | | ZED_XONE_GS | ZED X One with global shutter AR0234 sensor | | ZED_XONE_UHD | ZED X One with 4K rolling shutter IMX678 sensor | | ZED_XONE_HDR | ZED X One HDR | ## Values - `MODEL.ZED` - `MODEL.ZED_M` - `MODEL.ZED2` - `MODEL.ZED2i` - `MODEL.ZED_X` - `MODEL.ZED_XM` - `MODEL.ZED_X_NANO` - `MODEL.ZED_X_HDR` - `MODEL.ZED_X_HDR_MINI` - `MODEL.ZED_X_HDR_MAX` - `MODEL.VIRTUAL_ZED_X` - `MODEL.ZED_XONE_GS` - `MODEL.ZED_XONE_UHD` - `MODEL.ZED_XONE_HDR` - `MODEL.LAST` --- # MODULE *(enum)* Lists available module | MODULE | Description | |:---:|:---:| | ALL | All modules | | DEPTH | For the depth module (includes all 'measures' in retrieveMeasure) | | POSITIONAL_TRACKING | For the positional tracking module | | OBJECT_DETECTION | For the object detection module | | BODY_TRACKING | For the body tracking module | | SPATIAL_MAPPING | For the spatial mapping module | ## Values - `MODULE.ALL` - `MODULE.DEPTH` - `MODULE.POSITIONAL_TRACKING` - `MODULE.OBJECT_DETECTION` - `MODULE.BODY_TRACKING` - `MODULE.SPATIAL_MAPPING` - `MODULE.LAST` --- # OBJECT_ACCELERATION_PRESET *(enum)* Lists supported presets for maximum acceleration allowed for a given tracked object. | Enumerator | | |:---:|:---:| | DEFAULT | The ZED SDK will automatically determine the appropriate maximum acceleration. | | LOW | Suitable for objects with relatively low maximum acceleration (e.g., a person walking). | | MEDIUM | Suitable for objects with moderate maximum acceleration (e.g., a person running). | | HIGH | Suitable for objects with high maximum acceleration (e.g., a car accelerating, a kicked sports ball). | ## Values - `OBJECT_ACCELERATION_PRESET.DEFAULT` - `OBJECT_ACCELERATION_PRESET.LOW` - `OBJECT_ACCELERATION_PRESET.MEDIUM` - `OBJECT_ACCELERATION_PRESET.HIGH` - `OBJECT_ACCELERATION_PRESET.LAST` --- # OBJECT_ACTION_STATE *(enum)* Lists the different states of an object's actions. | Enumerator | | |:---:|:---:| | IDLE | The object is staying static. | | MOVING | The object is moving. | ## Values - `OBJECT_ACTION_STATE.IDLE` - `OBJECT_ACTION_STATE.MOVING` - `OBJECT_ACTION_STATE.LAST` --- # OBJECT_CLASS *(enum)* Lists available object classes. | OBJECT_CLASS | Description | |:---:|:---:| | PERSON | For people detection | | VEHICLE | For vehicle detection (cars, trucks, buses, motorcycles, etc.) | | BAG | For bag detection (backpack, handbag, suitcase, etc.) | | ANIMAL | For animal detection (cow, sheep, horse, dog, cat, bird, etc.) | | ELECTRONICS | For electronic device detection (cellphone, laptop, etc.) | | FRUIT_VEGETABLE | For fruit and vegetable detection (banana, apple, orange, carrot, etc.) | | SPORT | For sport-related object detection (sport ball, etc.) | ## Values - `OBJECT_CLASS.PERSON` - `OBJECT_CLASS.VEHICLE` - `OBJECT_CLASS.BAG` - `OBJECT_CLASS.ANIMAL` - `OBJECT_CLASS.ELECTRONICS` - `OBJECT_CLASS.FRUIT_VEGETABLE` - `OBJECT_CLASS.SPORT` - `OBJECT_CLASS.LAST` --- # OBJECT_DETECTION_MODEL *(enum)* Lists available models for the object detection module. | Enumerator | | |:---:|:---:| | MULTI_CLASS_BOX_FAST | Any objects, bounding box based. | | MULTI_CLASS_BOX_ACCURATE | Any objects, bounding box based, more accurate but slower than the base model. | | MULTI_CLASS_BOX_MEDIUM | Any objects, bounding box based, compromise between accuracy and speed. | | PERSON_HEAD_BOX_FAST | Bounding box detector specialized in person heads particularly well suited for crowded environments. The person localization is also improved. | | PERSON_HEAD_BOX_ACCURATE | Bounding box detector specialized in person heads, particularly well suited for crowded environments. The person localization is also improved, more accurate but slower than the base model. | | CUSTOM_BOX_OBJECTS | For external inference, using your own custom model and/or frameworks. This mode disables the internal inference engine, the 2D bounding box detection must be provided. | ## Values - `OBJECT_DETECTION_MODEL.MULTI_CLASS_BOX_FAST` - `OBJECT_DETECTION_MODEL.MULTI_CLASS_BOX_MEDIUM` - `OBJECT_DETECTION_MODEL.MULTI_CLASS_BOX_ACCURATE` - `OBJECT_DETECTION_MODEL.PERSON_HEAD_BOX_FAST` - `OBJECT_DETECTION_MODEL.PERSON_HEAD_BOX_ACCURATE` - `OBJECT_DETECTION_MODEL.CUSTOM_BOX_OBJECTS` - `OBJECT_DETECTION_MODEL.CUSTOM_YOLOLIKE_BOX_OBJECTS` - `OBJECT_DETECTION_MODEL.LAST` --- # OBJECT_FILTERING_MODE *(enum)* Lists supported bounding box preprocessing. | Enumerator | | |:---:|:---:| | NONE | The ZED SDK will not apply any preprocessing to the detected objects. | | NMS3D | The ZED SDK will remove objects that are in the same 3D position as an already tracked object (independent of class id). | | NMS3D_PER_CLASS | The ZED SDK will remove objects that are in the same 3D position as an already tracked object of the same class id. | ## Values - `OBJECT_FILTERING_MODE.NONE` - `OBJECT_FILTERING_MODE.NMS3D` - `OBJECT_FILTERING_MODE.NMS3D_PER_CLASS` - `OBJECT_FILTERING_MODE.LAST` --- # OBJECT_SUBCLASS *(enum)* List available object subclasses. Given as hint, when using object tracking an object can change of sl.OBJECT_SUBCLASS while keeping the same sl.OBJECT_CLASS (i.e.: frame n: MOTORBIKE, frame n+1: BICYCLE). | OBJECT_SUBCLASS | OBJECT_CLASS | |:---:|:---:| | PERSON | PERSON | | PERSON_HEAD | PERSON | | BICYCLE | VEHICLE | | CAR | VEHICLE | | MOTORBIKE | VEHICLE | | BUS | VEHICLE | | TRUCK | VEHICLE | | BOAT | VEHICLE | | BACKPACK | BAG | | HANDBAG | BAG | | SUITCASE | BAG | | BIRD | ANIMAL | | CAT | ANIMAL | | DOG | ANIMAL | | HORSE | ANIMAL | | SHEEP | ANIMAL | | COW | ANIMAL | | CELLPHONE | ELECTRONICS | | LAPTOP | ELECTRONICS | | BANANA | FRUIT_VEGETABLE | | APPLE | FRUIT_VEGETABLE | | ORANGE | FRUIT_VEGETABLE | | CARROT | FRUIT_VEGETABLE | | SPORTSBALL | SPORT | | MACHINERY | VEHICLE | ## Values - `OBJECT_SUBCLASS.PERSON` - `OBJECT_SUBCLASS.PERSON_HEAD` - `OBJECT_SUBCLASS.BICYCLE` - `OBJECT_SUBCLASS.CAR` - `OBJECT_SUBCLASS.MOTORBIKE` - `OBJECT_SUBCLASS.BUS` - `OBJECT_SUBCLASS.TRUCK` - `OBJECT_SUBCLASS.BOAT` - `OBJECT_SUBCLASS.BACKPACK` - `OBJECT_SUBCLASS.HANDBAG` - `OBJECT_SUBCLASS.SUITCASE` - `OBJECT_SUBCLASS.BIRD` - `OBJECT_SUBCLASS.CAT` - `OBJECT_SUBCLASS.DOG` - `OBJECT_SUBCLASS.HORSE` - `OBJECT_SUBCLASS.SHEEP` - `OBJECT_SUBCLASS.COW` - `OBJECT_SUBCLASS.CELLPHONE` - `OBJECT_SUBCLASS.LAPTOP` - `OBJECT_SUBCLASS.BANANA` - `OBJECT_SUBCLASS.APPLE` - `OBJECT_SUBCLASS.ORANGE` - `OBJECT_SUBCLASS.CARROT` - `OBJECT_SUBCLASS.SPORTSBALL` - `OBJECT_SUBCLASS.MACHINERY` - `OBJECT_SUBCLASS.LAST` --- # OBJECT_TRACKING_STATE *(enum)* Lists the different states of object tracking. | Enumerator | | |:---:|:---:| | OFF | The tracking is not yet initialized. The object id is not usable. | | OK | The object is tracked. | | SEARCHING | The object could not be detected in the image and is potentially occluded. The trajectory is estimated. | | TERMINATE | This is the last searching state of the track. The track will be deleted in the next sl.Camera.retrieve_objects(). | ## Values - `OBJECT_TRACKING_STATE.OFF` - `OBJECT_TRACKING_STATE.OK` - `OBJECT_TRACKING_STATE.SEARCHING` - `OBJECT_TRACKING_STATE.TERMINATE` - `OBJECT_TRACKING_STATE.LAST` --- # ODOMETRY_STATUS *(enum)* Report the status of current odom tracking. | Enumerator | | |:----------:|:---------------------------| | OK | The positional tracking module successfully tracked from the previous frame to the current frame. | | UNAVAILABLE | The positional tracking module cannot track the current frame. | | INSUFFICIENT_FEATURES | The positional tracking failed to track the current frame because it could not find enought features. | ## Values - `ODOMETRY_STATUS.OK` - `ODOMETRY_STATUS.UNAVAILABLE` - `ODOMETRY_STATUS.INSUFFICIENT_FEATURES` - `ODOMETRY_STATUS.LAST` --- # PLANE_TYPE *(enum)* Lists the available plane types detected based on the orientation. | Enumerator | | |:---:|:---:| | HORIZONTAL | Horizontal plane, such as a tabletop, floor, etc. | | VERTICAL | Vertical plane, such as a wall. | | UNKNOWN | Unknown plane orientation. | ## Values - `PLANE_TYPE.HORIZONTAL` - `PLANE_TYPE.VERTICAL` - `PLANE_TYPE.UNKNOWN` - `PLANE_TYPE.LAST` --- # POSITIONAL_TRACKING_FUSION_STATUS *(enum)* Report the status of the positional tracking fusion. | Enumerator | | |:----------:|:---------------------------| | VISUAL_INERTIAL | The positional tracking module is fusing visual and inertial data. | | VISUAL | The positional tracking module is fusing visual data only. | | INERTIAL | The positional tracking module is fusing inertial data only. | | GNSS | The positional tracking module is fusing GNSS data only. | | VISUAL_INERTIAL_GNSS | The positional tracking module is fusing visual, inertial, and GNSS data. | | VISUAL_GNSS | The positional tracking module is fusing visual and GNSS data. | | INERTIAL_GNSS | The positional tracking module is fusing inertial and GNSS data. | | UNAVAILABLE | The positional tracking module is unavailable. | ## Values - `POSITIONAL_TRACKING_FUSION_STATUS.VISUAL_INERTIAL` - `POSITIONAL_TRACKING_FUSION_STATUS.VISUAL` - `POSITIONAL_TRACKING_FUSION_STATUS.INERTIAL` - `POSITIONAL_TRACKING_FUSION_STATUS.GNSS` - `POSITIONAL_TRACKING_FUSION_STATUS.VISUAL_INERTIAL_GNSS` - `POSITIONAL_TRACKING_FUSION_STATUS.VISUAL_GNSS` - `POSITIONAL_TRACKING_FUSION_STATUS.INERTIAL_GNSS` - `POSITIONAL_TRACKING_FUSION_STATUS.UNAVAILABLE` - `POSITIONAL_TRACKING_FUSION_STATUS.LAST` --- # POSITIONAL_TRACKING_MODE *(enum)* Lists the mode of positional tracking that can be used. | Enumerator | | |:---:|:---:| | GEN_1 | Default mode. Fast and stable mode. Requires depth computation. Less robust than GEN_3. | | GEN_2 | Warning: DEPRECATED. | | GEN_3 | Fast and accurate, in both exploratory mode and mapped environments. Note: Can be used even if depth_mode is set to DEPTH_MODE::NONE. | ## Values - `POSITIONAL_TRACKING_MODE.GEN_1` - `POSITIONAL_TRACKING_MODE.GEN_2` - `POSITIONAL_TRACKING_MODE.GEN_3` --- # POSITIONAL_TRACKING_STATE *(enum)* Lists the different states of positional tracking. | Enumerator | | |:---:|:---:| | SEARCHING | Warning: DEPRECATED: This state is no longer in use. | | OK | The positional tracking is functioning normally. | | OFF | The positional tracking is currently disabled. | | FPS_TOO_LOW | The effective FPS is too low to provide accurate motion tracking results. Consider adjusting performance parameters (e.g., depth mode, camera resolution) to improve tracking quality.| | SEARCHING_FLOOR_PLANE | The camera is currently searching for the floor plane to establish its position relative to it. The world reference frame will be set afterward. | | UNAVAILABLE | The tracking module was unable to perform tracking from the previous frame to the current frame. | ## Values - `POSITIONAL_TRACKING_STATE.SEARCHING` - `POSITIONAL_TRACKING_STATE.OK` - `POSITIONAL_TRACKING_STATE.OFF` - `POSITIONAL_TRACKING_STATE.FPS_TOO_LOW` - `POSITIONAL_TRACKING_STATE.SEARCHING_FLOOR_PLANE` - `POSITIONAL_TRACKING_STATE.UNAVAILABLE` - `POSITIONAL_TRACKING_STATE.LAST` --- # POSITION_TYPE *(enum)* Lists the types of possible position outputs. | Enumerator | | |:---:|:---:| | RAW | The output position will be the raw position data. | | FUSION | The output position will be the fused position projected into the requested camera repository. | ## Values - `POSITION_TYPE.RAW` - `POSITION_TYPE.FUSION` - `POSITION_TYPE.LAST` --- # RECORDING_FORMAT *(enum)* Lists available recording formats for Lidar data. ## Values - `RECORDING_FORMAT.OSF` - `RECORDING_FORMAT.PCAP` - `RECORDING_FORMAT.PCD` - `RECORDING_FORMAT.AUTO` --- # REFERENCE_FRAME *(enum)* Lists possible types of position matrix used to store camera path and pose. | Enumerator | | |:---:|:---:| | WORLD | The transform of sl.Pose will contain the motion with reference to the world frame (previously called sl.PATH). | | CAMERA | The transform of sl.Pose will contain the motion with reference to the previous camera frame (previously called sl.POSE). | ## Values - `REFERENCE_FRAME.WORLD` - `REFERENCE_FRAME.CAMERA` - `REFERENCE_FRAME.LAST` --- # REGION_OF_INTEREST_AUTO_DETECTION_STATE *(enum)* Lists the different states of region of interest auto detection. | Enumerator | | |:---:|:---:| | RUNNING | The region of interest auto detection is initializing. | | READY | The region of interest mask is ready, if auto_apply was enabled, the region of interest mask is being used | | NOT_ENABLED | The region of interest auto detection is not enabled | ## Values - `REGION_OF_INTEREST_AUTO_DETECTION_STATE.RUNNING` - `REGION_OF_INTEREST_AUTO_DETECTION_STATE.READY` - `REGION_OF_INTEREST_AUTO_DETECTION_STATE.NOT_ENABLED` - `REGION_OF_INTEREST_AUTO_DETECTION_STATE.LAST` --- # RESOLUTION *(enum)* Lists available resolutions. **Note:** The VGA resolution does not respect the 640*480 standard to better fit the camera sensor (672*376 is used). **Warning:** All resolutions are not available for every camera. **Warning:** You can find the available resolutions for each camera in `our documentation `_. | Enumerator | | |:---:|:---:| | HD4K | 3856x2180 for imx678 mono | | QHDPLUS | 3800x1800 | | HD2K | 2208*1242 (x2) Available FPS: 15 | | HD1080 | 1920*1080 (x2) Available FPS: 15, 30 | | HD1200 | 1920*1200 (x2) Available FPS: 15, 30, 60 | | HD1536 | 1920*1536 (x2) Available FPS: 30 | | HD720 | 1280*720 (x2) Available FPS: 15, 30, 60 | | SVGA | 960*600 (x2) Available FPS: 15, 30, 60, 120 | | VGA | 672*376 (x2) Available FPS: 15, 30, 60, 100 | | XVGA | 960x768 (x2) Available FPS: 30 Only supported with ZED-X HDR lineup (One/Stereo) | | TXGA | 640x512 (x2) Available FPS: 30 Only supported with ZED-X HDR lineup (One/Stereo) | | AUTO | Select the resolution compatible with the camera: * ZED X/X Mini: HD1200* other cameras: HD720 | ## Values - `RESOLUTION.HD4K` - `RESOLUTION.QHDPLUS` - `RESOLUTION.HD2K` - `RESOLUTION.HD1080` - `RESOLUTION.HD1200` - `RESOLUTION.HD1536` - `RESOLUTION.HD720` - `RESOLUTION.SVGA` - `RESOLUTION.VGA` - `RESOLUTION.XVGA` - `RESOLUTION.TXGA` - `RESOLUTION.AUTO` - `RESOLUTION.LAST` --- # SENDER_ERROR_CODE *(enum)* Lists the types of error that can be raised during the Fusion by senders. | Enumerator | | |:---:|:---:| | DISCONNECTED | The sender has been disconnected. | | SUCCESS | Standard code for successful behavior. | | GRAB_ERROR | The sender encountered a grab error. | | INCONSISTENT_FPS | The sender does not run with a constant frame rate. | | FPS_TOO_LOW | The frame rate of the sender is lower than 10 FPS. | ## Values - `SENDER_ERROR_CODE.DISCONNECTED` - `SENDER_ERROR_CODE.SUCCESS` - `SENDER_ERROR_CODE.GRAB_ERROR` - `SENDER_ERROR_CODE.INCONSISTENT_FPS` - `SENDER_ERROR_CODE.FPS_TOO_LOW` --- # SENSORS_ERROR_CODE *(enum)* Lists error codes for the Sensors API. ## Values - `SENSORS_ERROR_CODE.STALE_DATA` - `SENSORS_ERROR_CODE.GNSS_DATA_NEED_FIX` - `SENSORS_ERROR_CODE.INVALID_COVARIANCE` - `SENSORS_ERROR_CODE.INVALID_TIMESTAMP` - `SENSORS_ERROR_CODE.CONFIGURATION_FALLBACK` - `SENSORS_ERROR_CODE.MOTION_SENSORS_DATA_REQUIRED` - `SENSORS_ERROR_CODE.CORRUPTED_FRAME` - `SENSORS_ERROR_CODE.SENSOR_REBOOTING` - `SENSORS_ERROR_CODE.SUCCESS` - `SENSORS_ERROR_CODE.FAILURE` - `SENSORS_ERROR_CODE.NO_GPU_COMPATIBLE` - `SENSORS_ERROR_CODE.NOT_ENOUGH_GPU_MEMORY` - `SENSORS_ERROR_CODE.SENSOR_NOT_DETECTED` - `SENSORS_ERROR_CODE.MOTION_SENSORS_NOT_INITIALIZED` - `SENSORS_ERROR_CODE.MOTION_SENSORS_NOT_AVAILABLE` - `SENSORS_ERROR_CODE.INVALID_RESOLUTION` - `SENSORS_ERROR_CODE.LOW_USB_BANDWIDTH` - `SENSORS_ERROR_CODE.CALIBRATION_FILE_NOT_AVAILABLE` - `SENSORS_ERROR_CODE.INVALID_CALIBRATION_FILE` - `SENSORS_ERROR_CODE.INVALID_SVO_FILE` - `SENSORS_ERROR_CODE.SVO_RECORDING_ERROR` - `SENSORS_ERROR_CODE.SVO_UNSUPPORTED_COMPRESSION` - `SENSORS_ERROR_CODE.END_OF_SVOFILE_REACHED` - `SENSORS_ERROR_CODE.INVALID_COORDINATE_SYSTEM` - `SENSORS_ERROR_CODE.INVALID_FIRMWARE` - `SENSORS_ERROR_CODE.INVALID_FUNCTION_PARAMETERS` - `SENSORS_ERROR_CODE.CUDA_ERROR` - `SENSORS_ERROR_CODE.SENSOR_NOT_INITIALIZED` - `SENSORS_ERROR_CODE.NVIDIA_DRIVER_OUT_OF_DATE` - `SENSORS_ERROR_CODE.INVALID_FUNCTION_CALL` - `SENSORS_ERROR_CODE.CORRUPTED_SDK_INSTALLATION` - `SENSORS_ERROR_CODE.INCOMPATIBLE_SDK_VERSION` - `SENSORS_ERROR_CODE.INVALID_AREA_FILE` - `SENSORS_ERROR_CODE.INCOMPATIBLE_AREA_FILE` - `SENSORS_ERROR_CODE.SENSOR_FAILED_TO_SETUP` - `SENSORS_ERROR_CODE.SENSOR_DETECTION_ISSUE` - `SENSORS_ERROR_CODE.CANNOT_START_SENSOR_STREAM` - `SENSORS_ERROR_CODE.NO_GPU_DETECTED` - `SENSORS_ERROR_CODE.PLANE_NOT_FOUND` - `SENSORS_ERROR_CODE.MODULE_NOT_COMPATIBLE_WITH_SENSOR` - `SENSORS_ERROR_CODE.MOTION_SENSORS_REQUIRED` - `SENSORS_ERROR_CODE.MODULE_NOT_COMPATIBLE_WITH_CUDA_VERSION` - `SENSORS_ERROR_CODE.DRIVER_FAILURE` - `SENSORS_ERROR_CODE.CAMERA_EXCEEDS_BANDWIDTH` - `SENSORS_ERROR_CODE.LAST` --- # SENSORS_EXECUTION_MODE *(enum)* Execution mode for the Sensors pipeline. | Enumerator | Description | |:---:|:---:| | EAGER | Synchronous — process() blocks, computes everything, returns. | | PIPELINED | Each device gets a worker thread; process() returns immediately after setup phase. | ## Values - `SENSORS_EXECUTION_MODE.EAGER` - `SENSORS_EXECUTION_MODE.PIPELINED` --- # SENSORS_REFERENCE_FRAME *(enum)* Lists available Sensors API reference frames. ## Values - `SENSORS_REFERENCE_FRAME.DEFAULT` - `SENSORS_REFERENCE_FRAME.SENSOR` - `SENSORS_REFERENCE_FRAME.BASELINK` - `SENSORS_REFERENCE_FRAME.WORLD` --- # SENSORS_SYNC_POLICY *(enum)* Lists available sync policies for pipelined mode. | Enumerator | Description | |:---:|:---:| | NONE | No temporal sync, each device returns its latest data. | | CLOSEST | Temporally align data across devices using the oldest "latest" timestamp. | | DROP_STALE | Same as CLOSEST, but returns error if data exceeds sync_tolerance. | ## Values - `SENSORS_SYNC_POLICY.NONE` - `SENSORS_SYNC_POLICY.CLOSEST` - `SENSORS_SYNC_POLICY.DROP_STALE` --- # SENSORS_TYPE *(enum)* Lists available sensor types for the Sensors API. | Enumerator | | |:---:|:---:| | CAMERA | Standard ZED camera. | | CAMERA_ONE | ZED X One camera. | | LIDAR | LiDAR sensor. | ## Values - `SENSORS_TYPE.CAMERA` - `SENSORS_TYPE.CAMERA_ONE` - `SENSORS_TYPE.LIDAR` --- # SENSORS_UNIT *(enum)* Lists available measurement units of onboard sensors. **Note:** Sensors are not available on sl.MODEL.ZED. | Enumerator | | |:---:|:---:| | M_SEC_2 | m/s² (acceleration) | | DEG_SEC | deg/s (angular velocity) | | U_T | μT (magnetic field) | | HPA | hPa (atmospheric pressure) | | CELSIUS | °C (temperature) | | HERTZ | Hz (frequency) | ## Values - `SENSORS_UNIT.M_SEC_2` - `SENSORS_UNIT.DEG_SEC` - `SENSORS_UNIT.U_T` - `SENSORS_UNIT.HPA` - `SENSORS_UNIT.CELSIUS` - `SENSORS_UNIT.HERTZ` --- # SENSOR_LOCATION *(enum)* Lists possible locations of temperature sensors. | Enumerator | | |:---:|:---:| | IMU | The temperature sensor is in the IMU. | | BAROMETER | The temperature sensor is in the barometer. | | ONBOARD_LEFT | The temperature sensor is next to the left image sensor. | | ONBOARD_RIGHT | The temperature sensor is next to the right image sensor. | ## Values - `SENSOR_LOCATION.IMU` - `SENSOR_LOCATION.BAROMETER` - `SENSOR_LOCATION.ONBOARD_LEFT` - `SENSOR_LOCATION.ONBOARD_RIGHT` - `SENSOR_LOCATION.LAST` --- # SENSOR_STATE *(enum)* Lists possible states of a sensor device. | Enumerator | | |:---:|:---:| | AVAILABLE | Indicates that the sensor can be opened. | | NOT_AVAILABLE | The sensor is not available. | ## Values - `SENSOR_STATE.AVAILABLE` - `SENSOR_STATE.NOT_AVAILABLE` - `SENSOR_STATE.LAST` --- # SENSOR_TYPE *(enum)* Lists available sensor types. **Note:** Sensors are not available on sl.MODEL.ZED. | Enumerator | | |:---:|:---:| | ACCELEROMETER | Three-axis accelerometer sensor to measure the inertial accelerations. | | GYROSCOPE | Three-axis gyroscope sensor to measure the angular velocities. | | MAGNETOMETER | Three-axis magnetometer sensor to measure the orientation of the device with respect to the Earth's magnetic field. | | BAROMETER | Barometer sensor to measure the atmospheric pressure. | ## Values - `SENSOR_TYPE.ACCELEROMETER` - `SENSOR_TYPE.GYROSCOPE` - `SENSOR_TYPE.MAGNETOMETER` - `SENSOR_TYPE.BAROMETER` --- # SIDE *(enum)* Lists possible sides on which to get data from. | Enumerator | | |:---:|:---:| | LEFT | Left side only. | | RIGHT | Right side only. | | BOTH | Left and right side. | ## Values - `SIDE.LEFT` - `SIDE.RIGHT` - `SIDE.BOTH` --- # SPATIAL_MAPPING_STATE *(enum)* Lists the different states of spatial mapping. | Enumerator | | |:---:|:---:| | INITIALIZING | The spatial mapping is initializing. | | OK | The depth and tracking data were correctly integrated in the mapping algorithm. | | NOT_ENOUGH_MEMORY | The maximum memory dedicated to the scanning has been reached. The mesh will no longer be updated. | | NOT_ENABLED | sl.Camera.enable_spatial_mapping() wasn't called or the scanning was stopped and not relaunched. | | FPS_TOO_LOW | The effective FPS is too low to give proper results for spatial mapping. Consider using performance parameters (sl.DEPTH_MODE.PERFORMANCE, sl.MAPPING_RESOLUTION.LOW, low camera resolution (RESOLUTION "sl.RESOLUTION.VGA/SVGA" or sl.RESOLUTION.HD720). | ## Values - `SPATIAL_MAPPING_STATE.INITIALIZING` - `SPATIAL_MAPPING_STATE.OK` - `SPATIAL_MAPPING_STATE.NOT_ENOUGH_MEMORY` - `SPATIAL_MAPPING_STATE.NOT_ENABLED` - `SPATIAL_MAPPING_STATE.FPS_TOO_LOW` - `SPATIAL_MAPPING_STATE.LAST` --- # SPATIAL_MAP_TYPE *(enum)* Lists the types of spatial maps that can be created. | Enumerator | | |:---:|:---:| | MESH | The geometry is represented by a set of vertices connected by edges and forming faces. No color information is available. | | FUSED_POINT_CLOUD | The geometry is represented by a set of 3D colored points. | ## Values - `SPATIAL_MAP_TYPE.MESH` - `SPATIAL_MAP_TYPE.FUSED_POINT_CLOUD` - `SPATIAL_MAP_TYPE.LAST` --- # SPATIAL_MEMORY_STATUS *(enum)* Report the status of current map tracking. | Enumerator | | |:-----------:|:---------------------------| | OK | The positional tracking module is operating normally. | | LOOP_CLOSED | The positional tracking module detected a loop and corrected its position. | | SEARCHING | The positional tracking module is searching for recognizable areas in the global map to relocate. | | INITIALIZING| Displayed until the cameras has acquired enough memory (Initial Area Mapping) or has found its first loop closure and is localized in the loaded area map (Lifelong Mapping/Localization). Users need to keep moving the camera for it to get updated. | | MAP_UPDATE | Displayed when the robot is mapping (Initial Area Mapping) or when the robot is getting out of the area map bounds (Lifelong Mapping). Displayed as “Tracking” when in exploratory mode with SLAM engaged. | | KNOWN_MAP | Displayed when the camera is localized within the loaded area map. | | LOST | Displayed when localization cannot operate anymore (camera completely obstructed, sudden localization jumps after being localized) in Mapping/ Localization modes. It can also include the case where the camera jumps or is located out of map bounds in Localization mode. This should be an indicator for users to stop the robot. | | OFF | Displayed when the spatial memory is turned off.| ## Values - `SPATIAL_MEMORY_STATUS.OK` - `SPATIAL_MEMORY_STATUS.LOOP_CLOSED` - `SPATIAL_MEMORY_STATUS.SEARCHING` - `SPATIAL_MEMORY_STATUS.INITIALIZING` - `SPATIAL_MEMORY_STATUS.MAP_UPDATE` - `SPATIAL_MEMORY_STATUS.KNOWN_MAP` - `SPATIAL_MEMORY_STATUS.LOST` - `SPATIAL_MEMORY_STATUS.OFF` - `SPATIAL_MEMORY_STATUS.NOT_ENOUGH_MEMORY_FOR_TRACKING` - `SPATIAL_MEMORY_STATUS.LAST` --- # STREAMING_CODEC *(enum)* Lists the different encoding types for image streaming. | Enumerator | | |:---:|:---:| | H264 | AVCHD/H264 encoding | | H265 | HEVC/H265 encoding | ## Values - `STREAMING_CODEC.H264` - `STREAMING_CODEC.H265` - `STREAMING_CODEC.LAST` --- # SVO_COMPRESSION_MODE *(enum)* Lists available compression modes for SVO recording. **Note:** LOSSLESS is an improvement of previous lossless compression (used in ZED Explorer), even if size may be bigger, compression time is much faster. | Enumerator | | |:---:|:---:| | LOSSLESS | PNG/ZSTD (lossless) CPU based compression. Average size: 42% of RAW | | H264 | H264 (AVCHD) GPU based compression. Average size: 1% of RAW Note: Requires a NVIDIA GPU. | | H265 | H265 (HEVC) GPU based compression. Average size: 1% of RAW Note: Requires a NVIDIA GPU. | | H264_LOSSLESS | H264 Lossless GPU/Hardware based compression. Average size: 25% of RAW Provides a SSIM/PSNR result (vs RAW) >= 99.9%. Note: Requires a NVIDIA GPU. | | H265_LOSSLESS | H265 Lossless GPU/Hardware based compression. Average size: 25% of RAW Provides a SSIM/PSNR result (vs RAW) >= 99.9%. Note: Requires a NVIDIA GPU. | ## Values - `SVO_COMPRESSION_MODE.LOSSLESS` - `SVO_COMPRESSION_MODE.H264` - `SVO_COMPRESSION_MODE.H265` - `SVO_COMPRESSION_MODE.H264_LOSSLESS` - `SVO_COMPRESSION_MODE.H265_LOSSLESS` - `SVO_COMPRESSION_MODE.LAST` --- # SVO_ENCODING_PRESET *(enum)* Lists available encoding presets for SVO recording. The preset controls the speed/quality tradeoff of the hardware encoder. | Enumerator | | |:---:|:---:| | ULTRAFAST | Fastest encoding, lowest quality. Maps to NVENC P1 / V4L2 ULTRAFAST. | | FAST | Fast encoding. Maps to NVENC P2 / V4L2 FAST. | | MEDIUM | Balanced speed/quality. Maps to NVENC P3 / V4L2 MEDIUM. | | SLOW | Slow encoding, higher quality. Maps to NVENC P5 / V4L2 SLOW. | | DEFAULT | Encoder default. Maps to NVENC P4 / V4L2 default. | ## Values - `SVO_ENCODING_PRESET.DEFAULT` - `SVO_ENCODING_PRESET.ULTRAFAST` - `SVO_ENCODING_PRESET.FAST` - `SVO_ENCODING_PRESET.MEDIUM` - `SVO_ENCODING_PRESET.SLOW` - `SVO_ENCODING_PRESET.LAST` --- # TENSOR_COLOR_FORMAT *(enum)* Lists available color formats for the Tensor. ## Values - `TENSOR_COLOR_FORMAT.GRAY` - `TENSOR_COLOR_FORMAT.Y` - `TENSOR_COLOR_FORMAT.RGB` - `TENSOR_COLOR_FORMAT.BGR` - `TENSOR_COLOR_FORMAT.RGBA` - `TENSOR_COLOR_FORMAT.BGRA` --- # TENSOR_LAYOUT *(enum)* Lists available memory layouts for the Tensor. ## Values - `TENSOR_LAYOUT.NCHW` - `TENSOR_LAYOUT.NHWC` --- # TENSOR_PIXEL_TYPE *(enum)* Lists available pixel data types for the Tensor elements. ## Values - `TENSOR_PIXEL_TYPE.FLOAT` - `TENSOR_PIXEL_TYPE.HALF` - `TENSOR_PIXEL_TYPE.UCHAR` --- # TIMESTAMP_CLOCK *(enum)* Lists available clock sources for SDK timestamps. Selects the clock used internally by the SDK to timestamp images and sensor data. Both image and IMU timestamps always use the same selected clock, ensuring coherent results. **Note:** This is a process-wide setting. Use set_timestamp_clock() before opening any camera. | Enumerator | | |:---:|:---:| | SYSTEM_CLOCK | Timestamps use system (wall-clock) time. Affected by NTP/PTP adjustments. | | MONOTONIC_CLOCK | Timestamps use monotonic clock (CLOCK_MONOTONIC). Immune to system clock step adjustments. | **Note:** On ZED X cameras, full end-to-end immunity also requires ZED X driver version 1.4.2 or later. With older drivers the IMU itself can pause briefly when the system time is set backward; the SDK emits a warning at camera open and resumes IMU delivery automatically. Other cameras are unaffected. ## Values - `TIMESTAMP_CLOCK.SYSTEM_CLOCK` - `TIMESTAMP_CLOCK.MONOTONIC_CLOCK` - `TIMESTAMP_CLOCK.LAST` --- # TIME_REFERENCE *(enum)* Lists possible time references for timestamps or data. | Enumerator | | |:---:|:---:| | IMAGE | The requested timestamp or data will be at the time of the frame extraction. | | CURRENT | The requested timestamp or data will be at the time of the function call. | ## Values - `TIME_REFERENCE.IMAGE` - `TIME_REFERENCE.CURRENT` - `TIME_REFERENCE.LAST` --- # TYPE_OF_INPUT_TYPE *(enum)* Lists input types in the ZED SDK. | Enumerator | | |:---:|:---:| | USB_ID, | USB input from an id | | USB_SERIAL, | USB input from a serial number | | SVO_FILE, | SVO file input | | STREAM, | STREAM input (requires to use Camera.enableStreaming "enableStreaming()" / Camera.disableStreaming "disableStreaming()"" on the "sender" side) | | GMSL_ID, | GMSL input from an id (only on NVIDIA Jetson) | | GMSL_SERIAL, | GMSL input from a serial number (only on NVIDIA Jetson) | | GMSL_PORT, | GMSL input from a physical GMSL port (only on NVIDIA Jetson) | | AUTO, | AUTO input type, automatically selects the right input type between USB and GMSL | ## Values - `TYPE_OF_INPUT_TYPE.USB_ID` - `TYPE_OF_INPUT_TYPE.USB_SERIAL` - `TYPE_OF_INPUT_TYPE.SVO_FILE` - `TYPE_OF_INPUT_TYPE.STREAM` - `TYPE_OF_INPUT_TYPE.GMSL_ID` - `TYPE_OF_INPUT_TYPE.GMSL_SERIAL` - `TYPE_OF_INPUT_TYPE.GMSL_PORT` - `TYPE_OF_INPUT_TYPE.AUTO` - `TYPE_OF_INPUT_TYPE.LAST` --- # UNIT *(enum)* Lists available units for measures. | Enumerator | | |:---:|:---:| | MILLIMETER | International System (1/1000 meters) | | CENTIMETER | International System (1/100 meters) | | METER | International System (1 meter) | | INCH | Imperial Unit (1/12 feet) | | FOOT | Imperial Unit (1 foot) | ## Values - `UNIT.MILLIMETER` - `UNIT.CENTIMETER` - `UNIT.METER` - `UNIT.INCH` - `UNIT.FOOT` - `UNIT.LAST` --- # VIDEO_SETTINGS *(enum)* Lists available camera settings for the camera (contrast, hue, saturation, gain, ...). **Warning:** All VIDEO_SETTINGS are not supported for all camera models. You can find the supported VIDEO_SETTINGS for each ZED camera in our `documentation `_. GAIN and EXPOSURE are linked in auto/default mode (see sl.Camera.set_camera_settings()). | Enumerator | | |:---:|:---:| | BRIGHTNESS | Brightness control Affected value should be between 0 and 8. Note: Not available for ZED X/X Mini cameras. | | CONTRAST | Contrast control Affected value should be between 0 and 8. Note: Not available for ZED X/X Mini cameras. | | HUE | Hue control Affected value should be between 0 and 11. Note: Not available for ZED X/X Mini cameras. | | SATURATION | Saturation control Affected value should be between 0 and 8. | | SHARPNESS | Digital sharpening control Affected value should be between 0 and 8. | | GAMMA | ISP gamma control Affected value should be between 1 and 9. | | GAIN | Gain control Affected value should be between 0 and 100 for manual control. Note: If EXPOSURE is set to -1 (automatic mode), then GAIN will be automatic as well. | | EXPOSURE | Exposure control Affected value should be between 0 and 100 for manual control. The exposition is mapped linearly in a percentage of the following max values. Special case for ``EXPOSURE = 0`` that corresponds to 0.17072ms. The conversion to milliseconds depends on the framerate: * 15fps & ``EXPOSURE = 100`` -> 19.97ms* 30fps & ``EXPOSURE = 100`` -> 19.97ms* 60fps & ``EXPOSURE = 100`` -> 10.84072ms* 100fps & ``EXPOSURE = 100`` -> 10.106624ms | | AEC_AGC | Defines if the GAIN and EXPOSURE are in automatic mode or not. Setting GAIN or EXPOSURE values will automatically set this value to 0. | | AEC_AGC_ROI | Defines the region of interest for automatic exposure/gain computation. To be used with the dedicated Camera.set_camera_settings_roi "set_camera_settings_roi()" / Camera.get_camera_settings_roi "get_camera_settings_roi()" methods. | | WHITEBALANCE_TEMPERATURE | Color temperature control Affected value should be between 2800 and 6500 with a step of 100.Note: Setting a value will automatically set WHITEBALANCE_AUTO to 0. | | WHITEBALANCE_AUTO | Defines if the white balance is in automatic mode or not. | | LED_STATUS | Status of the front LED of the camera. Set to 0 to disable the light, 1 to enable the light. Default value is on. Note: Requires camera firmware 1523 at least. | | EXPOSURE_TIME | Exposure time control in microseconds. Note: Only available for ZED X/X Mini cameras, ZED-XOne GS and ZED-XOne UHD cameras.| | ANALOG_GAIN | Analog gain (sensor) control in mDB. The range is defined by Jetson DTS and by default [1000-16000]. Note: Only available for ZED X/X Mini, ZED-XOne GS and ZED-XOne UHD cameras.| | DIGITAL_GAIN | Digital gain (ISP) as a factor. The range is defined by Jetson DTS and by default [1-256]. Note: Only available for ZED X/X Mini, ZED-XOne GS and ZED-XOne UHD cameras.| | AUTO_EXPOSURE_TIME_RANGE | Range of exposure auto control in micro seconds. Used with Camera.set_camera_settings_range "set_camera_settings_range()". Min/max range between max range defined in DTS. By default: [28000 - or 19000] us. Note: Only available for ZED X/X Mini cameras. | | AUTO_ANALOG_GAIN_RANGE | Range of sensor gain in automatic control. Used with Camera.set_camera_settings_range "set_camera_settings_range()". Min/max range between max range defined in DTS. By default: [1000 - 16000] mdB. Note: Only available for ZED X/X Mini cameras. | | AUTO_DIGITAL_GAIN_RANGE | Range of digital ISP gain in automatic control. Used with Camera.set_camera_settings_range "set_camera_settings_range()". Min/max range between max range defined in DTS. By default: [1 - 256]. Note: Only available for ZED X/X Mini cameras. | | EXPOSURE_COMPENSATION | Exposure-target compensation made after auto exposure. Reduces the overall illumination target by factor of F-stops. Affected value should be between 0 and 100 (mapped between [-2.0,2.0]). Default value is 50, i.e. no compensation applied. Note: Only available for ZED X/X Mini cameras. | | DENOISING | Level of denoising applied on both left and right images. Affected value should be between 0 and 100. Default value is 50. Note: Only available for ZED X/X Mini cameras. | | SCENE_ILLUMINANCE | Level of illuminance of the scene. Can be used to determine the level of light in the scene and adjust settings accordingly. Note: Read-only control. Available for ZED-X/Xmini cameras. Value provided in [0.1x]Lux for ZED-X / ZED-X Mini / ZED-XOne GS and ZED-XOne UHD cameras. | | AE_ANTIBANDING | AE anti-banding mode. Affected value should be between 0 and 3. 0: OFF, 1: AUTO, 2: 50Hz, 3: 60Hz. Default value is 0 (OFF). Note: Only available for non-HDR GMSL cameras (e.g. ZED X, ZED X Mini, ZED X One GS, etc.). | ## Values - `VIDEO_SETTINGS.BRIGHTNESS` - `VIDEO_SETTINGS.CONTRAST` - `VIDEO_SETTINGS.HUE` - `VIDEO_SETTINGS.SATURATION` - `VIDEO_SETTINGS.SHARPNESS` - `VIDEO_SETTINGS.GAMMA` - `VIDEO_SETTINGS.GAIN` - `VIDEO_SETTINGS.EXPOSURE` - `VIDEO_SETTINGS.AEC_AGC` - `VIDEO_SETTINGS.AEC_AGC_ROI` - `VIDEO_SETTINGS.WHITEBALANCE_TEMPERATURE` - `VIDEO_SETTINGS.WHITEBALANCE_AUTO` - `VIDEO_SETTINGS.LED_STATUS` - `VIDEO_SETTINGS.EXPOSURE_TIME` - `VIDEO_SETTINGS.ANALOG_GAIN` - `VIDEO_SETTINGS.DIGITAL_GAIN` - `VIDEO_SETTINGS.AUTO_EXPOSURE_TIME_RANGE` - `VIDEO_SETTINGS.AUTO_ANALOG_GAIN_RANGE` - `VIDEO_SETTINGS.AUTO_DIGITAL_GAIN_RANGE` - `VIDEO_SETTINGS.EXPOSURE_COMPENSATION` - `VIDEO_SETTINGS.DENOISING` - `VIDEO_SETTINGS.SCENE_ILLUMINANCE` - `VIDEO_SETTINGS.AE_ANTIBANDING` - `VIDEO_SETTINGS.LAST` --- # VIEW *(enum)* Lists available views. | Enumerator | | |:---:|:---:| | LEFT | Left BGRA image. Each pixel contains 4 unsigned char (B, G, R, A). Type: sl.MAT_TYPE.U8_C4 | | RIGHT | Right BGRA image. Each pixel contains 4 unsigned char (B, G, R, A). Type: sl.MAT_TYPE.U8_C4 | | LEFT_GRAY | Left gray image. Each pixel contains 1 unsigned char. Type: sl.MAT_TYPE.U8_C1| | RIGHT_GRAY | Right gray image. Each pixel contains 1 unsigned char. Type: sl.MAT_TYPE.U8_C1| | LEFT_NV12_UNRECTIFIED | Left NV12 unrectified image. Each pixel contains 1 unsigned char for Y plane and 1 unsigned char for UV plane. Type: sl.MAT_TYPE.NV12| | RIGHT_NV12_UNRECTIFIED | Right NV12 unrectified image. Each pixel contains 1 unsigned char for Y plane and 1 unsigned char for UV plane. Type: sl.MAT_TYPE.NV12| | LEFT_UNRECTIFIED | Left BGRA unrectified image. Each pixel contains 4 unsigned char (B, G, R, A). Type: sl.MAT_TYPE.U8_C4 | | RIGHT_UNRECTIFIED | Right BGRA unrectified image. Each pixel contains 4 unsigned char (B, G, R, A). Type: sl.MAT_TYPE.U8_C4 | | LEFT_UNRECTIFIED_GRAY | Left gray unrectified image. Each pixel contains 1 unsigned char. Type: sl.MAT_TYPE.U8_C1 | | RIGHT_UNRECTIFIED_GRAY | Right gray unrectified image. Each pixel contains 1 unsigned char. Type: sl.MAT_TYPE.U8_C1 | | SIDE_BY_SIDE | Left and right image (the image width is therefore doubled). Each pixel contains 4 unsigned char (B, G, R, A). Type: sl.MAT_TYPE.U8_C4 | | DEPTH | Color rendering of the depth. Each pixel contains 4 unsigned char (B, G, R, A). Type: sl.MAT_TYPE.U8_C4 Note: Use sl.MEASURE.DEPTH with sl.Camera.retrieve_measure() to get depth values. | | CONFIDENCE | Color rendering of the depth confidence. Each pixel contains 4 unsigned char (B, G, R, A). Type: sl.MAT_TYPE.U8_C4 Note: Use sl.MEASURE.CONFIDENCE with sl.Camera.retrieve_measure() to get confidence values. | | NORMALS | Color rendering of the normals. Each pixel contains 4 unsigned char (B, G, R, A). Type: sl.MAT_TYPE.U8_C4 Note: Use sl.MEASURE.NORMALS with sl.Camera.retrieve_measure() to get normal values. | | DEPTH_RIGHT | Color rendering of the right depth mapped on right sensor. Each pixel contains 4 unsigned char (B, G, R, A). Type: sl.MAT_TYPE.U8_C4 Note: Use sl.MEASURE.DEPTH_RIGHT with sl.Camera.retrieve_measure() to get depth right values. | | NORMALS_RIGHT | Color rendering of the normals mapped on right sensor. Each pixel contains 4 unsigned char (B, G, R, A). Type: sl.MAT_TYPE.U8_C4 Note: Use sl.MEASURE.NORMALS_RIGHT with sl.Camera.retrieve_measure() to get normal right values. | ## Values - `VIEW.LEFT` - `VIEW.RIGHT` - `VIEW.LEFT_GRAY` - `VIEW.RIGHT_GRAY` - `VIEW.LEFT_NV12_UNRECTIFIED` - `VIEW.RIGHT_NV12_UNRECTIFIED` - `VIEW.LEFT_UNRECTIFIED` - `VIEW.RIGHT_UNRECTIFIED` - `VIEW.LEFT_UNRECTIFIED_GRAY` - `VIEW.RIGHT_UNRECTIFIED_GRAY` - `VIEW.SIDE_BY_SIDE` - `VIEW.DEPTH` - `VIEW.CONFIDENCE` - `VIEW.NORMALS` - `VIEW.DEPTH_RIGHT` - `VIEW.NORMALS_RIGHT` - `VIEW.LEFT_BGRA` - `VIEW.LEFT_BGR` - `VIEW.RIGHT_BGRA` - `VIEW.RIGHT_BGR` - `VIEW.LEFT_UNRECTIFIED_BGRA` - `VIEW.LEFT_UNRECTIFIED_BGR` - `VIEW.RIGHT_UNRECTIFIED_BGRA` - `VIEW.RIGHT_UNRECTIFIED_BGR` - `VIEW.SIDE_BY_SIDE_BGRA` - `VIEW.SIDE_BY_SIDE_BGR` - `VIEW.SIDE_BY_SIDE_GRAY` - `VIEW.SIDE_BY_SIDE_UNRECTIFIED_BGRA` - `VIEW.SIDE_BY_SIDE_UNRECTIFIED_BGR` - `VIEW.SIDE_BY_SIDE_UNRECTIFIED_GRAY` - `VIEW.DEPTH_BGRA` - `VIEW.DEPTH_BGR` - `VIEW.DEPTH_GRAY` - `VIEW.CONFIDENCE_BGRA` - `VIEW.CONFIDENCE_BGR` - `VIEW.CONFIDENCE_GRAY` - `VIEW.NORMALS_BGRA` - `VIEW.NORMALS_BGR` - `VIEW.NORMALS_GRAY` - `VIEW.DEPTH_RIGHT_BGRA` - `VIEW.DEPTH_RIGHT_BGR` - `VIEW.DEPTH_RIGHT_GRAY` - `VIEW.NORMALS_RIGHT_BGRA` - `VIEW.NORMALS_RIGHT_BGR` - `VIEW.NORMALS_RIGHT_GRAY` - `VIEW.LAST` --- # VIEW_COLOR_MAP *(enum)* Lists available colormaps for Lidar data visualization. ## Values - `VIEW_COLOR_MAP.AUTO` - `VIEW_COLOR_MAP.GREY` - `VIEW_COLOR_MAP.MAGMA` - `VIEW_COLOR_MAP.INFERNO` - `VIEW_COLOR_MAP.PLASMA` - `VIEW_COLOR_MAP.VIRIDIS` - `VIEW_COLOR_MAP.SPEZIA` - `VIEW_COLOR_MAP.TURBO` - `VIEW_COLOR_MAP.JET` - `VIEW_COLOR_MAP.BONE` - `VIEW_COLOR_MAP.GNUPLOT2` --- # VOXELIZATION_MODE *(enum)* Controls how voxel size adapts with depth. | Enumerator | | |:---:|:---:| | FIXED | No adaptation. Voxel size is used uniformly everywhere. | | STEREO_UNCERTAINTY | Quadratic growth matching stereo depth noise. | | LINEAR | Linear growth with depth. Suits lidar/ToF sensors. | ## Values - `VOXELIZATION_MODE.FIXED` - `VOXELIZATION_MODE.STEREO_UNCERTAINTY` - `VOXELIZATION_MODE.LINEAR` - `VOXELIZATION_MODE.LAST` --- # pyzed.sl — Module Functions ### `_initialize_error_codes() -> None` Lists error codes in the ZED SDK. | Enumerator | | |:---:|:---:| | SENSOR_CONFIGURATION_CHANGED | The sensor's configuration was changed externally while streaming. If auto_recovery_on_config_change is enabled, the SDK will automatically reconnect. | | POTENTIAL_CALIBRATION_ISSUE | The camera has a potential calibration issue. | | CONFIGURATION_FALLBACK | The operation could not proceed with the target configuration but did success with a fallback. | | SENSORS_DATA_REQUIRED | The input data does not contains the high frequency sensors data, this is usually because it requires newer SVO/Streaming. In order to work this modules needs inertial data present in it input. | | CORRUPTED_FRAME | The image is corrupted with invalid colors (green/purple images). This indicates a serious hardware or driver issue. | CAMERA_REBOOTING | The camera is currently rebooting. | | SUCCESS | Standard code for successful behavior. | | FAILURE | Standard code for unsuccessful behavior. | | NO_GPU_COMPATIBLE | No GPU found or CUDA capability of the device is not supported. | | NOT_ENOUGH_GPU_MEMORY | Not enough GPU memory for this depth mode. Try a different mode (such as PERFORMANCE), or increase the minimum depth value (see InitParameters.depth_minimum_distance). | | CAMERA_NOT_DETECTED | No camera was detected. | | SENSORS_NOT_INITIALIZED | The MCU that controls the sensors module has an invalid serial number. You can try to recover it by launching the **ZED Diagnostic** tool from the command line with the option ``-r``. | | SENSORS_NOT_AVAILABLE | A camera with sensor is detected but the sensors (IMU, barometer, ...) cannot be opened. Only the MODEL.ZED does not has sensors. Unplug/replug is required. | | INVALID_RESOLUTION | In case of invalid resolution parameter, such as an upsize beyond the original image size in Camera.retrieve_image. | | LOW_USB_BANDWIDTH | Insufficient bandwidth for the correct use of the camera. This issue can occur when you use multiple cameras or a USB 2.0 port. | | CALIBRATION_FILE_NOT_AVAILABLE | The calibration file of the camera is not found on the host machine. Use **ZED Explorer** or **ZED Calibration** to download the factory calibration file. | | INVALID_CALIBRATION_FILE | The calibration file is not valid. Try to download the factory calibration file or recalibrate your camera using **ZED Calibration**. | | INVALID_SVO_FILE | The provided SVO file is not valid. | | SVO_RECORDING_ERROR | An error occurred while trying to record an SVO (not enough free storage, invalid file, ...). | | SVO_UNSUPPORTED_COMPRESSION | An SVO related error, occurs when NVIDIA based compression cannot be loaded. | | END_OF_SVOFILE_REACHED | SVO end of file has been reached. No frame will be available until the SVO position is reset. | | INVALID_COORDINATE_SYSTEM | The requested coordinate system is not available. | | INVALID_FIRMWARE | The firmware of the camera is out of date. Update to the latest version. | | INVALID_FUNCTION_PARAMETERS | Invalid parameters have been given for the function. | | CUDA_ERROR | A CUDA error has been detected in the process, in sl.Camera.grab() or sl.Camera.retrieve_xxx() only. Activate verbose in sl.Camera.open() for more info. | | CAMERA_NOT_INITIALIZED | The ZED SDK is not initialized. Probably a missing call to sl.Camera.open(). | | NVIDIA_DRIVER_OUT_OF_DATE | Your NVIDIA driver is too old and not compatible with your current CUDA version. | | INVALID_FUNCTION_CALL | The call of the function is not valid in the current context. Could be a missing call of sl.Camera.open(). | | CORRUPTED_SDK_INSTALLATION | The ZED SDK was not able to load its dependencies or some assets are missing. Reinstall the ZED SDK or check for missing dependencies (cuDNN, TensorRT). | | INCOMPATIBLE_SDK_VERSION | The installed ZED SDK is incompatible with the one used to compile the program. | | INVALID_AREA_FILE | The given area file does not exist. Check the path. | | INCOMPATIBLE_AREA_FILE | The area file does not contain enough data to be used or the sl.DEPTH_MODE used during the creation of the area file is different from the one currently set. | | CAMERA_FAILED_TO_SETUP | Failed to open the camera at the proper resolution. Try another resolution or make sure that the UVC driver is properly installed. | | CAMERA_DETECTION_ISSUE | Your camera can not be opened. Try replugging it to another port or flipping the USB-C connector (if there is one). | | CANNOT_START_CAMERA_STREAM | Cannot start the camera stream. Make sure your camera is not already used by another process or blocked by firewall or antivirus. | | NO_GPU_DETECTED | No GPU found. CUDA is unable to list it. Can be a driver/reboot issue. | | PLANE_NOT_FOUND | Plane not found. Either no plane is detected in the scene, at the location or corresponding to the floor, or the floor plane doesn't match the prior given. | | MODULE_NOT_COMPATIBLE_WITH_CAMERA | The module you try to use is not compatible with your camera sl.MODEL. Note: sl.MODEL.ZED does not has an IMU and does not support the AI modules. | | MOTION_SENSORS_REQUIRED | The module needs the sensors to be enabled (see InitParameters.sensors_required). | | MODULE_NOT_COMPATIBLE_WITH_CUDA_VERSION | The module needs a newer version of CUDA. | | DRIVER_FAILURE | The drivers initialization has failed. When using gmsl cameras, try restarting with sudo systemctl restart zed_x_daemon.service. | | CAMERA_EXCEEDS_BANDWIDTH | The camera configuration exceeds available PHY CSI bandwidth (GMSL). Reduce resolution or FPS, or adjust hardware configuration. | ### `_initialize_fusion_error_codes() -> None` Lists the types of error that can be raised by the Fusion. | Enumerator | | |:---:|:---:| | GNSS_DATA_NEED_FIX | GNSS Data need fix status in order to run fusion. | | GNSS_DATA_COVARIANCE_MUST_VARY | Ingested covariance data must vary between ingest. | | BODY_FORMAT_MISMATCH | The senders are using different body formats. Consider changing them. | | NOT_ENABLED | The following module was not enabled. | | SOURCE_MISMATCH | Some sources are provided by SVO and others by LIVE stream. | | CONNECTION_TIMED_OUT | Connection timed out. Unable to reach the sender. Verify the sender's IP/port. | | SHARED_MEMORY_LEAK | Intra-process shared memory allocation issue. Multiple connections to the same data. | | INVALID_IP_ADDRESS | The provided IP address format is incorrect. Please provide the IP in the format 'a.b.c.d', where (a, b, c, d) are numbers between 0 and 255. | | CONNECTION_ERROR | Something goes bad in the connection between sender and receiver. | | FAILURE | Standard code for unsuccessful behavior. | | SUCCESS | Standard code for successful behavior. | | FUSION_INCONSISTENT_FPS | Significant differences observed between sender's FPS. | | FUSION_FPS_TOO_LOW | At least one sender has an FPS lower than 10 FPS. | | INVALID_TIMESTAMP | Problem detected with the ingested timestamp. Sample data will be ignored. | | INVALID_COVARIANCE | Problem detected with the ingested covariance. Sample data will be ignored. | | NO_NEW_DATA_AVAILABLE | All data from all sources has been consumed. No new data is available for processing. | ### `_reconstruct_input_type(input_type_enum, configuration) -> None` Lists input types in the ZED SDK. | Enumerator | | |:---:|:---:| | USB_ID, | USB input from an id | | USB_SERIAL, | USB input from a serial number | | SVO_FILE, | SVO file input | | STREAM, | STREAM input (requires to use Camera.enableStreaming "enableStreaming()" / Camera.disableStreaming "disableStreaming()"" on the "sender" side) | | GMSL_ID, | GMSL input from an id (only on NVIDIA Jetson) | | GMSL_SERIAL, | GMSL input from a serial number (only on NVIDIA Jetson) | | GMSL_PORT, | GMSL input from a physical GMSL port (only on NVIDIA Jetson) | | AUTO, | AUTO input type, automatically selects the right input type between USB and GMSL | ### `_reconstruct_mat(np_data, mat_type_value, name='', timestamp_ns=0, verbose=False) -> None` ### `_resolve_data_pointer(ptr) -> None` Structure containing information of a single camera (serial number, model, calibration, etc.) That information about the camera will be returned by Camera.get_camera_information() **Note:** This object is meant to be used as a read-only container, editing any of its fields won't impact the SDK. **Warning:** CalibrationParameters are returned in COORDINATE_SYSTEM.IMAGE , they are not impacted by the InitParameters.coordinate_system ### `apply_transform(mat, transform, memory_type: MEM=MEM.BOTH) -> ERROR_CODE` Apply a transformation (rotation and translation) to a point cloud matrix. :param mat: (in/out) point cloud matrix to transform, can be either a MAT_TYPE.F32_C4 (the fourth value will be preserved as it contains the color information) or a MAT_TYPE.F32_C3. :param transform: the transformation (rotation + translation) to apply to each point. :param memory_type: define which memory should be transformed from mat. If MEM.BOTH is specified, the function will automatically detect which memory is allocated and transform accordingly (GPU preferred if both are allocated). :return: ERROR_CODE.SUCCESS if everything went well, ERROR_CODE.FAILURE otherwise. **Note:** This is useful for transforming point clouds between different reference frames (e.g., sensor to world frame). ### `blob_from_image(mat1: Mat, mat2: Mat, resolution: Resolution, scale: float, mean: tuple, stdev: tuple, keep_aspect_ratio: bool, swap_RB_channels: bool) -> ERROR_CODE` Convert an image into a GPU Tensor in planar channel configuration (NCHW), ready to use for deep learning model :param image_in: input image to convert :param tensor_out: output GPU tensor :param resolution_out: resolution of the output image, generally square, although not mandatory :param scalefactor: Scale factor applied to each pixel value, typically to convert the char value into [0-1] float :param mean: mean, statistic to normalized the pixel values, applied AFTER the scale. For instance for imagenet statistics the mean would be sl::float3(0.485, 0.456, 0.406) :param stddev: standard deviation, statistic to normalized the pixel values, applied AFTER the scale. For instance for imagenet statistics the standard deviation would be sl::float3(0.229, 0.224, 0.225) :param keep_aspect_ratio: indicates if the original width and height ratio should be kept using padding (sometimes refer to as letterboxing) or if the image should be stretched :param swap_RB_channels: indicates if the Red and Blue channels should be swapped (RGB<->BGR or RGBA<->BGRA) :return: ERROR_CODE : The error code gives information about the success of the function Example usage, for a 416x416 squared RGB image (letterboxed), with a scale factor of 1/255, and using the imagenet statistics for normalization: image = sl.Mat() blob = sl.Mat() resolution = sl.Resolution(416,416) scale = 1.0/255.0 # Scale factor to apply to each pixel value keep_aspect_ratio = True # Add padding to keep the aspect ratio swap_RB_channels = True # ZED SDK outputs BGR images, so we need to swap the R and B channels zed.retrieve_image(image, sl.VIEW.LEFT, type=sl.MEM.GPU) # Get the ZED image (GPU only is more efficient in that case) err = sl.blob_from_image(image, blob, resolution, scale, (0.485, 0.456, 0.406), (0.229, 0.224, 0.225), keep_aspect_ratio, swap_RB_channels) # By default the blob is in GPU memory, you can move it to CPU memory if needed blob.update_cpu_from_gpu() ### `blob_from_images(mats, mat_out, resolution, scale, mean, stdev, keep_aspect_ratio, swap_rb_channels) -> ERROR_CODE` Convert a list of images into a GPU Tensor in planar channel configuration (NCHW), ready to use for deep learning model :param mats: input images to convert :param mat_out: output GPU tensor batched :param resolution: resolution of the output image, generally square, although not mandatory :param scale: Scale factor applied to each pixel value, typically to convert the char value into [0-1] float :param mean: mean, statistic to normalized the pixel values, applied AFTER the scale. For instance for imagenet statistics the mean would be sl::float3(0.485, 0.456, 0.406) :param stdev: standard deviation, statistic to normalized the pixel values, applied AFTER the scale. For instance for imagenet statistics the standard deviation would be sl::float3(0.229, 0.224, 0.225) :param keep_aspect_ratio: indicates if the original width and height ratio should be kept using padding (sometimes refer to as letterboxing) or if the image should be stretched :param swap_rb_channels: indicates if the Red and Blue channels should be swapped (RGB<->BGR or RGBA<->BGRA) :return: ERROR_CODE.SUCCESS if everything went well, ERROR_CODE.FAILURE otherwise. ### `check_ai_model_status(model: AI_MODELS, gpu_id=0) -> dict` Checks if a corresponding optimized engine is found for the requested Model based on your rig configuration. :return: The status of the given model for the specified GPU. ### `compute_rotation_matrix_from_gravity(axis_to_align, gravity) -> Rotation` Compute the rotation matrix from the gravity vector : the rotation can used to find the world rotation from the gravity of an IMU :param axis_to_align: define the axis to align with the gravity, for instance : to align the "y" axis, axis_to_align = (0, 1, 0)' :param gravity: the gravity vector, acceleration set by an IMU :return: Rotation : rotation matrix, useful for Camera.detectFloorPlane as a gravity prior ### `convert_coordinate_system_mat(mat, src: COORDINATE_SYSTEM, dst: COORDINATE_SYSTEM, memory_type: MEM) -> ERROR_CODE` Change the coordinate system of a matrix. :param mat: (in/out) matrix to transform, can be either a MAT_TYPE.F32_C4 (the fourth value will be ignored as it contained the color information) or a MAT_TYPE.F32_C3. :param src: the current coordinate system of mat. :param dst: the destination coordinate system for mat. :param memory_type: define which memory should be transformed from mat. :return: ERROR_CODE.SUCCESS if everything went well, ERROR_CODE.FAILURE otherwise. */ ### `convert_coordinate_system_transform(transform, src: COORDINATE_SYSTEM, dst: COORDINATE_SYSTEM) -> ERROR_CODE` Change the coordinate system of a transform matrix. :param transform: (in/out) matrix to transform :param src: the current coordinate system of transform. :param dst: the destination coordinate system for transform. :return: ERROR_CODE.SUCCESS if everything went well, ERROR_CODE.FAILURE otherwise. ### `convert_image(image_in, image_signed) -> ERROR_CODE` Convert Image format from Unsigned char to Signed char, designed for Unreal Engine pipeline, works on GPU memory. :param image_in: input image to convert :param image_signed: output image to converted :return: ERROR_CODE.SUCCESS if everything went well, ERROR_CODE.FAILURE otherwise. **Note:** If the Output Mat does not satisfies the requirements, it is freed and re-allocated. ### `convert_unit_mat(mat, src: UNIT, dst: UNIT, memory_type: MEM) -> ERROR_CODE` Change the unit of a matrix. :param mat: (in/out) matrix to transform, can be either a MAT_TYPE::F32_C4 (the fourth value will be ignored as it contained the color information), MAT_TYPE::F32_C3 or a MAT_TYPE::F32_C1. :param src: the current unit of mat. :param dst: the destination unit for mat. :param mem: define which memory should be transformed from mat. :return: ERROR_CODE.SUCCESS if everything went well, ERROR_CODE.FAILURE otherwise. ### `convert_unit_transform(transform, src: UNIT, dst: UNIT) -> ERROR_CODE` Change the unit (of the translations) of a transform matrix. :param transform: (in/out) matrix to transform :param src: the current unit of transform. :param dst: the destination unit for transform. :return: ERROR_CODE.SUCCESS if everything went well, ERROR_CODE.FAILURE otherwise. ### `download_ai_model(model: AI_MODELS, gpu_id=0) -> None` Downloads the requested model. :return: sl.ERROR_CODE.SUCCESS if the model is already download. ### `generate_unique_id() -> None` Generate a UUID like unique id to help identify and track AI detections. ### `generate_virtual_stereo_serial_number(serial_left, serial_right) -> uint` Generate a unique identifier for virtual stereo based on the serial numbers of the two ZED Ones :param serial_l: Serial number of the left camera. :param serial_r: Serial number of the right camera. :return: A unique hash for the given pair of serial numbers, or 0 if an error occurred (e.g: same serial number). ### `get_available_camera_fps() -> list` Available camera FPS. Those values are not available for all cameras/resolutions. Use the isAvailable() function to check if a specific camera/resolution/fps is available. **Note:** The ZED SDK will automatically select the best available FPS for the camera/resolution if AUTO is selected. ### `get_coordinate_transform_conversion_3f(src: COORDINATE_SYSTEM, dst: COORDINATE_SYSTEM) -> Matrix3f` Get the coordinate transform conversion matrix to change coordinate system. :param src: the source coordinate system. :param dst: the destination coordinate system. :return: Matrix3f : transformation matrix, to apply to a float3 point simply multiply by this matrix (pt_coord_dst = tf_matrix * pt_coord_src). ### `get_coordinate_transform_conversion_4f(src: COORDINATE_SYSTEM, dst: COORDINATE_SYSTEM) -> Matrix4f` Get the coordinate transform conversion matrix to change coordinate system. :param src: the source coordinate system. :param dst: the destination coordinate system. :return: Matrix4f : transformation matrix, to apply to a float4 point simply multiply by this matrix (pt_coord_dst = tf_matrix * pt_coord_src). ### `get_current_timestamp() -> Timestamp` Class containing a set of parameters for the plane detection functionality. The default constructor sets all parameters to their default settings. **Note:** Parameters can be adjusted by the user. ### `get_idx(part: BODY_18_PARTS) -> int` Return associated index of each sl.BODY_18_PARTS. ### `get_idx_34(part: BODY_34_PARTS) -> int` Return associated index of each sl.BODY_34_PARTS. ### `get_idx_38(part: BODY_38_PARTS) -> int` Return associated index of each sl.BODY_38_PARTS. ### `get_max_system_clock_step_ms() -> float` Returns the current system-clock step clamp in milliseconds. See set_max_system_clock_step_ms. ### `get_object_class(subclass: OBJECT_SUBCLASS) -> OBJECT_CLASS` Get the object class from a specific subclass. :param subclass: the object subclass. :return: the corresponding object class. ### `get_object_subclass_as_coco(subclass: OBJECT_SUBCLASS) -> int` Get the COCO object subclass from a specific subclass. :param subclass: the object subclass. :return: the corresponding COCO object subclass. ### `get_object_subclasses(obj_class: OBJECT_CLASS) -> list` Get the list of object subclasses for a specific object class. :param obj_class: the object class. :return: list of corresponding object subclasses. ### `get_resolution(resolution: RESOLUTION) -> Resolution` Gets the corresponding sl.Resolution from an sl.RESOLUTION. :param resolution: The wanted sl.RESOLUTION. :return: The sl.Resolution corresponding to sl.RESOLUTION given as argument. ### `get_timestamp_clock() -> None` Returns the clock source currently used for SDK timestamps. :return: The active TIMESTAMP_CLOCK. ### `get_unit_scale(src: UNIT, dst: UNIT) -> float` Get the unit factor to change units. :param src: the source coordinate system. :param dst: the destination coordinate system. :return: float : unit scale (pt_coord_dst = factor * pt_coord_src). ### `get_zed_sdk_runtime_version() -> tuple` Returns the ZED SDK version currently installed on the computer. Where ret is -1 if the ZED SDK was not found, -2 if the ZED SDK version wasn't found, 0 otherwise. :return: ret, major, minor, patch. ### `is_FPS_available(fps, resolution: RESOLUTION, camera_model: MODEL) -> bool` Check if a frame rate is available for a given resolution and camera model :param fps: Frame rate to check :param resolution: Resolution to check :param camera_model: The camera model to check ### `is_HDR_available(resolution: RESOLUTION, camera_model: MODEL) -> bool` Check if a resolution for a given camera model is available for HDR :param resolution: Resolution to check :param camera_model: The camera model to check ### `is_camera_one(camera_model: MODEL) -> bool` Check if the camera is a ZED One (Monocular) or ZED (Stereo) :param camera_model: The camera model to check ### `is_fps_available(fps, resolution: RESOLUTION, camera_model: MODEL) -> bool` Test if a specific resolution/fps combination is available for the specified camera model. :param fps: The wanted fps. :param resolution: The wanted resolution. :param camera_model: The wanted camera model. :return: True if the resolution is available for the camera model, false otherwise. ### `is_resolution_available(resolution: RESOLUTION, camera_model: MODEL) -> bool` Check if a resolution is available for a given camera model :param resolution: Resolution to check :param camera_model: The camera model to check ### `is_resolution_available(resolution: RESOLUTION, camera_model: MODEL) -> bool` Test if a specific resolution is available for the specified camera model. :param resolution: The wanted resolution. :param camera_model: The wanted camera model. :return: True if the resolution is available for the camera model, false otherwise. ### `load_json_file(filepath) -> str` Load a JSON content from a file. :param filepath: path to the file to load. :return: JSON content if the file has been loaded correctly, empty string otherwise. ### `optimize_ai_model(model: AI_MODELS, gpu_id=0) -> None` Optimizes the requested model (and download the model if it is not present on the host). :return: sl.ERROR_CODE.SUCCESS if the model is well optimized. ### `read_fusion_configuration(json_config_filename, coord_sys: COORDINATE_SYSTEM, unit: UNIT) -> None` Read a Configuration JSON string to configure a fusion process. :param json_config_filename: The string containing the configuration (it will be parsed as JSON). :param coord_sys: Defines the COORDINATE_SYSTEM of the Fusion World Pose. :param unit: Defines the UNIT of the Fusion World Pose. :return: A vector of FusionConfiguration for all the cameras present in the configuration file. **Note:** Empty if no data were found for the requested camera. ### `read_fusion_configuration_file(json_config_filename: str, coord_system: COORDINATE_SYSTEM, unit: UNIT) -> list[FusionConfiguration]` Read a Configuration JSON file to configure a fusion process. :param json_config_filename: The name of the JSON file containing the configuration. :param coord_sys: The COORDINATE_SYSTEM in which you want the World Pose to be in. :param unit: The UNIT in which you want the World Pose to be in. :return: A list of FusionConfiguration for all the camera present in the file. **Note:** Empty if no data were found for the requested camera. ### `read_fusion_configuration_file_from_serial(self, json_config_filename: str, serial_number: int, coord_system: COORDINATE_SYSTEM, unit: UNIT) -> FusionConfiguration` Read a configuration JSON file to configure a fusion process. :param json_config_filename: The name of the JSON file containing the configuration. :param serial_number: The serial number of the ZED Camera you want to retrieve. :param coord_system: The COORDINATE_SYSTEM in which you want the World Pose to be in. :param unit: The UNIT in which you want the World Pose to be in. :return: A FusionConfiguration for the requested camera. **Note:** Empty if no data were found for the requested camera. ### `read_fusion_configuration_json(fusion_configuration: dict, coord_system: COORDINATE_SYSTEM, unit: UNIT) -> list[FusionConfiguration]` Read a Configuration JSON to configure a fusion process. :param fusion_configuration: The JSON containing the configuration. :param coord_sys: The COORDINATE_SYSTEM in which you want the World Pose to be in. :param unit: The UNIT in which you want the World Pose to be in. :return: A list of FusionConfiguration for all the camera present in the file. **Note:** Empty if no data were found for the requested camera. ### `reset_benchmark_timer() -> None` Reset the internal benchmark timer. When setting the env var `ZED_SDK_BENCHMARK_MODE=1`, it triggers an internal timer measurement. See zed-benchmarks for an example usage details. When calling this function, the internal timer is reset to zero. It is recommended to call this function right before starting the benchmarked code section and after a warm-up phase. ### `save_json_file(filepath, content, merge) -> bool` Save a JSON content into a file. :param filepath: path to the file to save. :param content: JSON content to save. :param merge: if true, will merge the content with existing file content. :return: true if the file has been saved correctly, false otherwise. ### `set_max_system_clock_step_ms(limit_ms: float) -> None` Sets the maximum system-clock step (milliseconds) the SDK will follow per sample when the host clock is adjusted backward (NTP/PTP step, manual date change). Only meaningful in SYSTEM_CLOCK mode (no effect in MONOTONIC_CLOCK). Forward clock movement always passes through instantly. :param limit_ms: Clamp threshold in milliseconds. - default (setter not called): 4 ms/sample. Safe for slew-only NTP/PTP. - any positive value: custom threshold. - 0.0: freeze the captured offset; ignore subsequent movement. - any negative value (e.g. -1.0): disable clamping. Step corrections propagate instantly. Recommended for PTP setups with step corrections. **Cheat sheet:** | Setup | Recommended value | |:---:|:---:| | Desktop / systemd-timesyncd (slew-only) | default | | PTP with `ptp4l --step_threshold=0` | default | | PTP with step corrections expected | -1.0 | | Deterministic timestamps, ignore host clock entirely | use MONOTONIC_CLOCK instead | **Note:** Process-wide. Environment variable ZED_SDK_MAX_SYSTEM_CLOCK_STEP_MS, when set, always wins over this setter (ops-side override). Call before opening any camera. ### `set_timestamp_clock(clock) -> None` Sets the clock source used for all SDK timestamps (images and sensors). This is a process-wide setting shared by all Camera and CameraOne instances. :param clock: The desired TIMESTAMP_CLOCK. **Note:** Call this before opening any camera. ### `sleep_ms(time: int) -> None` Blocks the execution of the current thread for **time milliseconds. :param time: Number of milliseconds to wait. ### `sleep_us(time: int) -> None` Blocks the execution of the current thread for **time microseconds. :param time: Number of microseconds to wait. ### `to_verbose(err: ERROR_CODE) -> str` Provide a concise sl.ERROR_CODE string. :param err: the sl.ERROR_CODE to convert. :return: A concise sl.ERROR_CODE string for the user. ### `write_configuration_file(json_config_filename: str, fusion_configurations: list, coord_sys: COORDINATE_SYSTEM, unit: UNIT) -> None` Write a Configuration JSON file to configure a fusion process. :param json_config_filename: The name of the JSON that will contain the information. :param conf: A list of FusionConfiguration listing all the camera configurations. :param coord_sys: The COORDINATE_SYSTEM in which the World Pose is. :param unit: The UNIT in which the World Pose is.