# ZED SDK 5.3.1 — cpp API reference > Per-symbol API reference for the ZED SDK cpp 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). > > All *Parameters structs additionally provide save(filename)/load(filename) > and encode(string)/decode(string) JSON serialization helpers plus == > and != comparison operators; these are omitted below for brevity. ## Contents - sl::Camera - sl::InitParameters - sl::RuntimeParameters - sl::Mat - sl - sl::CameraParameters - sl::CalibrationParameters - sl::Pose - sl::SensorsData - sl::PositionalTrackingParameters - sl::RecordingParameters - sl::StreamingParameters - sl::ObjectDetectionParameters - sl::BodyTrackingParameters - sl::Bodies - sl::BodiesBatch - sl::BodyData - sl::CameraIdentifier - sl::CameraOne - sl::Chunk - sl::CommunicationParameters - sl::CustomBoxObjectData - sl::CustomMaskObjectData - sl::ECEF - sl::ENU - sl::FusedPointCloud - sl::FusedPositionalTrackingStatus - sl::Fusion - sl::GNSSData - sl::GeoConverter - sl::GeoPose - sl::InputType - sl::KeyFrame - sl::Landmark - sl::Landmark2D - sl::LatLng - sl::Lidar - sl::Matrix3f - sl::Matrix4f - sl::Mesh - sl::MeshFilterParameters - sl::ObjectData - sl::Objects - sl::ObjectsBatch - sl::Orientation - sl::Plane - sl::PointCloudChunk - sl::PositionalTrackingStatus - sl::Rect - sl::Rotation - sl::SensorDeviceIdentifier - sl::Sensors - sl::String - sl::Tensor - sl::Transform - sl::Translation - sl::UTM - sl::Vector2 - sl::Vector3 - sl::Vector4 - sl::AI_Model_status - sl::BatchParameters - sl::BodyTrackingFusionParameters - sl::BodyTrackingFusionRuntimeParameters - sl::BodyTrackingRuntimeParameters - sl::BodyTrackingSensorsParameters - sl::BodyTrackingSensorsRuntimeParameters - sl::CameraConfiguration - sl::CameraInformation - sl::CameraMetrics - sl::CameraOneConfiguration - sl::CameraOneInformation - sl::CustomObjectDetectionProperties - sl::CustomObjectDetectionRuntimeParameters - sl::DeviceProperties - sl::FusionConfiguration - sl::FusionMetrics - sl::GNSSCalibrationParameters - sl::HealthStatus - sl::InitFusionParameters - sl::InitLidarParameters - sl::InitParametersOne - sl::InitSensorsParameters - sl::LidarCalibration - sl::LidarDeviceProperties - sl::LidarInformation - sl::LidarSensorConfiguration - sl::ObjectDetectionFusionParameters - sl::ObjectDetectionRuntimeParameters - sl::ObjectDetectionSensorsParameters - sl::ObjectTrackingParameters - sl::PlaneDetectionParameters - sl::PositionalTrackingFusionParameters - sl::PositionalTrackingLidarParameters - sl::PositionalTrackingSensorsParameters - sl::RawBuffer - sl::RecordingLidarParameters - sl::RecordingSensorsParameters - sl::RecordingStatus - sl::RegionOfInterestParameters - sl::Resolution - sl::RuntimeSensorsParameters - sl::SVOData - sl::SensorList - sl::SensorParameters - sl::SensorsConfiguration - sl::SensorsData::BarometerData - sl::SensorsData::IMUData - sl::SensorsData::MagnetometerData - sl::SensorsData::TemperatureData - sl::Sensors::ImplDeleter - sl::SpatialMappingFusionParameters - sl::SpatialMappingParameters - sl::StreamingProperties - sl::StreamingSensorList - sl::StreamingSensorsParameters - sl::SynchronizationParameter - sl::TensorParameters - sl::Timestamp - sl::VoxelMeasureParameters - std::hash< sl::CameraIdentifier > - std::hash< sl::String > - sl_zed/CameraOne.hpp - sl_zed/Camera.hpp - utils/Core.hpp - sl_fusion/Fusion.hpp - sl_lidar/Lidar.hpp - mapping/Mesh.hpp - sl_sensors/Sensors.hpp - add-on.txt - sl_zed - mapping - sl_fusion - sl_sensors - sl_core - utils - include - sl_lidar - migration-guide-4-0.md - release-notes.md - sl_fusion/sl_fusion/defines.hpp - sl_zed/sl_zed/defines.hpp - utils/types.hpp - std --- # sl::Camera **Module:** **Video Module** This class serves as the primary interface between the camera and the various features provided by the SDK. More... `#include ` ## Detailed Description ```cpp class sl::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 sl::Camera class like this: ```cpp #include using namespace sl; int main(int argc, char **argv) { // --- Initialize a Camera object and open the ZED // Create a ZED camera object Camera zed; // Set configuration parameters InitParameters init_params; init_params.camera_resolution = RESOLUTION::HD720; // Use HD720 video mode for USB cameras // init_params.camera_resolution = RESOLUTION::HD1200; // Use HD1200 video mode for GMSL cameras init_params.camera_fps = 60; // Set fps at 60 // Open the camera ERROR_CODE err = zed.open(init_params); if (err != ERROR_CODE::SUCCESS) { std::cout << err << " exit program " << std::endl; return -1; } // --- Main loop grabbing images and depth values // Capture 50 frames and stop int i = 0; Mat image, depth; while (i < 50) { // Grab an image if (zed.grab() == ERROR_CODE::SUCCESS) { // A new image is available if grab() returns SUCCESS // Display a pixel color zed.retrieveImage(image, VIEW::LEFT); // Get the left image sl::uchar4 centerBGRA; image.getValue(image.getWidth() / 2, image.getHeight() / 2, ¢erBGRA); std::cout << "Image " << i << " center pixel B: " << (int)centerBGRA[0] << " G: " << (int)centerBGRA[1] << " R: " << (int)centerBGRA[2] << std::endl; // Display a pixel depth zed.retrieveMeasure(depth, MEASURE::DEPTH); // Get the depth map float centerDepth; depth.getValue(depth.getWidth() / 2, depth.getHeight() / 2, ¢erDepth); std::cout << "Image " << i << " center depth: " << centerDepth << std::endl; i++; } } // --- Close the Camera zed.close(); return 0; } ``` ## Public Functions Documentation ### function retrieveImage ```cpp ERROR_CODE retrieveImage( Mat & mat, VIEW view =VIEW::LEFT, MEM type =MEM::CPU, Resolution image_size =Resolution(0, 0), cudaStream_t stream =0 ) ``` Retrieves images from the camera (or SVO file). **Parameters**: * **mat** : The sl::Mat to store the image. The method will create the Mat if necessary at the proper resolution. If already created, it will just update its data (CPU or GPU depending on the MEM type). * **view** : Defines the image you want (see VIEW). Default : VIEW::LEFT. * **type** : Defines on which memory the image should be allocated. Default: MEM::CPU. * **image_size** : If specified, define the resolution of the output sl::Mat. If set to Resolution(0,0), the camera resolution or InitParameters::maximum_working_resolution will be taken, whichever is the smallest. Default: (0,0). 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 the function sl::setEnvironmentVariable("ZED_SDK_DISABLE_AUTO_RETRIEVE_RESOLUTION", "1") at the beginning of the code. * **stream** : If passed, the CUDA stream to use for GPU calls. **Return**: * ERROR_CODE::SUCCESS if the method succeeded. * ERROR_CODE::INVALID_FUNCTION_PARAMETERS if the view mode requires a module not enabled (VIEW::DEPTH with DEPTH_MODE::NONE for example). * ERROR_CODE::INVALID_RESOLUTION if the resolution is higher than one provided by getCameraInformation().camera_configuration.resolution. * ERROR_CODE::FAILURE if another error occurred. **Note**: As this method retrieves the images grabbed by the grab() method, it should be called afterward. **Warning**: * A sl::Mat resolution higher than the camera resolution **cannot** be requested. * If VIEW is VIEW::LEFT_NV12_UNRECTIFIED or VIEW::RIGHT_NV12_UNRECTIFIED, **image_size** must be native, and **type** must be MEM::GPU. 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 retrieveMeasure(). **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 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 getCameraInformation().camera_configuration.resolution. However, you can request custom resolutions. For example, requesting a smaller image can help you speed up your application. ```cpp Mat leftImage; //create sl::Mat objects to store the image while (true) { // Grab an image if (zed.grab() == ERROR_CODE::SUCCESS) { // A new image is available if grab() returns SUCCESS zed.retrieveImage(leftImage, VIEW::LEFT); // Get the rectified left image // Display the center pixel colors sl::uchar4 leftCenter; leftImage.getValue(leftImage.getWidth() / 2, leftImage.getHeight() / 2, &leftCenter); std::cout << "left image color B: " << (int)leftCenter[0] << " G: " << (int)leftCenter[1] << " R: " << (int)leftCenter[2] << std::endl; } } ``` ### function retrieveImage ```cpp ERROR_CODE retrieveImage( RawBuffer & raw_buffer ) ``` Retrieve the native raw camera buffer in NV12 format for zero-copy processing. **Parameters**: * **raw_buffer** : The RawBuffer object to fill with the native buffer reference. **Return**: * ERROR_CODE::SUCCESS if the method succeeded. * ERROR_CODE::CAMERA_NOT_INITIALIZED if the camera is not opened. * ERROR_CODE::FAILURE if no buffer is available. **Note**: * This method must be called after a successful grab(). * The buffer is in NV12 format (semi-planar YUV 4:2:0). * The RawBuffer uses RAII - it will automatically release when it goes out of scope. * Only one RawBuffer should be held at a time. Holding multiple buffers may block the capture pipeline. **Warning**: **DO NOT manually destroy the NvBufSurface buffers** returned by getRawBuffer() or getRawBufferRight(). The SDK owns these buffers. Destroying them will cause crashes. This method provides direct access to the native capture buffer (Argus NvBufSurface on Jetson, or CUDA texture) without any data copying. This is ideal for custom processing pipelines that want to work directly with the camera's native buffer format. The returned RawBuffer is a zero-copy wrapper that maintains a reference to the internal buffer. When the RawBuffer is destroyed or release() is called, the buffer is returned to the capture pipeline for reuse. ```cpp Camera zed; InitParameters init_params; zed.open(init_params); while (true) { if (zed.grab() == ERROR_CODE::SUCCESS) { RawBuffer raw; if (zed.retrieveImage(raw) == ERROR_CODE::SUCCESS) { // Get NvBufSurface pointers void* nvbufLeft = raw.getRawBuffer(); void* nvbufRight = raw.getRawBufferRight(); // Cast and use with Argus/NVMM APIs // auto* surfLeft = static_cast(nvbufLeft); // Buffer automatically released when 'raw' goes out of scope } } } ``` ### function retrieveTensor ```cpp ERROR_CODE retrieveTensor( Tensor & dest, const TensorParameters & params, cudaStream_t stream =0 ) ``` Retrieved a sl::Tensor, containing the input image pre-processed for inference with SVO or live camera. **Parameters**: * **dest** : The Tensor to store the pre-processed input image for inference. * **params** : Options to configure the pre-processing steps applied to the input image. * **stream** : If passed, the CUDA stream to use for GPU calls. 0 by default. **Return**: * ERROR_CODE::SUCCESS if the method succeeded. * ERROR_CODE::INVALID_FUNCTION_PARAMETERS if the provided params are invalid. * ERROR_CODE::CAMERA_NOT_INITIALIZED if the camera is not opened. * ERROR_CODE::FAILURE if another error occurred. **Note**: * This method requires that the camera has been opened in either LIVE mode, SVO mode or STREAM mode. * The retrieved Tensor is allocated on the GPU, so ensure that your system has sufficient GPU memory to accommodate the Tensor size. 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. ### function getCameraSettings ```cpp ERROR_CODE getCameraSettings( VIDEO_SETTINGS settings, int & setting ) ``` Returns the current value of the requested camera setting (gain, brightness, hue, exposure, etc.). **Parameters**: * **settings** : The requested setting. * **setting** : The setting variable to fill. **Return**: ERROR_CODE to indicate if the method was successful. If successful, setting will be filled with the corresponding value. **Note**: * The method works only if the camera is open in LIVE or STREAM mode. * Settings are not exported in the SVO file format. Possible values (range) of each setting are available here. ```cpp int gain; err = zed.getCameraSettings(VIDEO_SETTINGS::GAIN, gain); if (err == ERROR_CODE::SUCCESS) std::cout << "Current gain value: " << gain << std::endl; ``` ### function getCameraSettings ```cpp ERROR_CODE getCameraSettings( VIDEO_SETTINGS settings, int & min_val, int & max_val ) ``` Fills the current values of the requested settings for VIDEO_SETTINGS that supports two values (min/max). **Parameters**: * **settings** : The requested setting. * **min_val** : The setting minimum variable to fill. * **max_val** : The setting maximum variable to fill. **Return**: ERROR_CODE to indicate if the method was successful. If successful, setting will be filled with the corresponding value. **Note**: Works only with ZED X that supports low-level controls 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. ```cpp int aec_range_min = 0; int aec_range_max = 0; sl::ERROR_CODE err = zed.getCameraSettings(sl::VIDEO_SETTINGS::AUTO_EXPOSURE_TIME_RANGE, aec_range_min, aec_range_max); std::cout << "Current AUTO_EXPOSURE_TIME_RANGE range values ==> min: " << aec_range_min << " max: " << aec_range_max << std::endl; ``` ### function getCameraSettings ```cpp ERROR_CODE getCameraSettings( VIDEO_SETTINGS settings, Rect & roi, sl::SIDE side =sl::SIDE::BOTH ) ``` Overloaded method for VIDEO_SETTINGS::AEC_AGC_ROI which takes a Rect as parameter. **Parameters**: * **settings** : Must be set at VIDEO_SETTINGS::AEC_AGC_ROI, otherwise the method will have no impact. * **roi** : Roi that will be filled. * **side** : SIDE on which to get the ROI from. **Return**: ERROR_CODE to indicate if the method was successful. If successful, roi will be filled with the corresponding values. **Note**: * Works only if the camera is open in LIVE or STREAM mode with VIDEO_SETTINGS::AEC_AGC_ROI. * It will return ERROR_CODE::INVALID_FUNCTION_CALL or ERROR_CODE::INVALID_FUNCTION_PARAMETERS otherwise. ### function setCameraSettings ```cpp ERROR_CODE setCameraSettings( VIDEO_SETTINGS settings, int value =VIDEO_SETTINGS_VALUE_AUTO ) ``` Sets the value of the requested camera setting (gain, brightness, hue, exposure, etc.). **Parameters**: * **settings** : The setting to be set. * **value** : The value to set. Default: auto mode **Return**: ERROR_CODE to indicate if the method was successful. **Note**: The method works only if the camera is open in LIVE or STREAM mode. **Warning**: Setting VIDEO_SETTINGS::EXPOSURE or VIDEO_SETTINGS::GAIN to default will automatically sets the other to default. This method only applies for VIDEO_SETTINGS that require a single value. Possible values (range) of each setting are available here. ```cpp // Set the gain to 50 zed.setCameraSettings(VIDEO_SETTINGS::GAIN, 50); ``` ### function setCameraSettings ```cpp ERROR_CODE setCameraSettings( VIDEO_SETTINGS settings, int min, int max ) ``` Sets the value of the requested camera setting that supports two values (min/max). **Parameters**: * **settings** : The setting to be set. * **min** : The minimum value that can be reached (-1 or 0 gives full range). * **max** : The maximum value that can be reached (-1 or 0 gives full range). **Return**: ERROR_CODE to indicate if the method was successful. **Note**: The method works only if the camera is open in LIVE or STREAM mode. **Warning**: If VIDEO_SETTINGS settings is not supported or min >= max, it will return ERROR_CODE::INVALID_FUNCTION_PARAMETERS. This method only works with the following VIDEO_SETTINGS: * VIDEO_SETTINGS::AUTO_EXPOSURE_TIME_RANGE * VIDEO_SETTINGS::AUTO_ANALOG_GAIN_RANGE * VIDEO_SETTINGS::AUTO_DIGITAL_GAIN_RANGE Possible values (range) of each setting are available here. ```cpp // For ZED X based product, set the automatic exposure from 2ms to 5ms. Expected exposure time cannot go beyond those values zed.setCameraSettings(VIDEO_SETTINGS::AUTO_EXPOSURE_TIME_RANGE, 2000, 5000); ``` ### function setCameraSettings ```cpp ERROR_CODE setCameraSettings( VIDEO_SETTINGS settings, Rect roi, sl::SIDE side =sl::SIDE::BOTH, bool reset =false ) ``` Overloaded method for VIDEO_SETTINGS::AEC_AGC_ROI which takes a Rect as parameter. **Parameters**: * **settings** : Must be set at VIDEO_SETTINGS::AEC_AGC_ROI, otherwise the method will have no impact. * **roi** : Rect that defines the target to be applied for AEC/AGC computation. Must be given according to camera resolution. * **side** : SIDE on which to be applied for AEC/AGC computation. * **reset** : Cancel the manual ROI and reset it to the full image. **Return**: ERROR_CODE to indicate if the method was successful. **Note**: Works only if the camera is open in LIVE or STREAM mode with VIDEO_SETTINGS::AEC_AGC_ROI. ### function getCameraSettingsRange ```cpp ERROR_CODE getCameraSettingsRange( VIDEO_SETTINGS settings, int & min, int & max ) ``` Get the range for the specified camera settings VIDEO_SETTINGS as min/max value. **Parameters**: * **settings** : Must be set at a valid VIDEO_SETTINGS that accepts a min/max range and available for the current camera model. * **min** : The minimum value that can be reached to be filled. * **max** : The maximum value that can be reached to be filled. **Return**: ERROR_CODE to indicate if the method was successful. ### function isCameraSettingSupported ```cpp bool isCameraSettingSupported( VIDEO_SETTINGS setting ) ``` Test if the video setting is supported by the camera. **Parameters**: * **setting** : The video setting to test **Return**: true if the VIDEO_SETTINGS is supported by the camera, false otherwise ### function getCurrentFPS ```cpp float getCurrentFPS() ``` Returns the current framerate at which the grab() method is successfully called. **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. The returned value is based on the difference of camera timestamps between two successful grab() calls. ```cpp int current_fps = zed.getCurrentFPS(); std::cout << "Current framerate: " << current_fps << std::endl; ``` ### function getTimestamp ```cpp Timestamp getTimestamp( sl::TIME_REFERENCE reference_time ) ``` Returns the timestamp in the requested TIME_REFERENCE. **Parameters**: * **reference_time** : 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. * When requesting the TIME_REFERENCE::IMAGE timestamp, the UNIX nanosecond timestamp of the latest 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 1 or 2 frame-time based on the fps (ex: 16.6ms to 33ms 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. ```cpp Timestamp last_image_timestamp = zed.getTimestamp(TIME_REFERENCE::IMAGE); Timestamp current_timestamp = zed.getTimestamp(TIME_REFERENCE::CURRENT); std::cout << "Latest image timestamp: " << last_image_timestamp << "ns from Epoch." << std::endl; std::cout << "Current timestamp: " << current_timestamp << "ns from Epoch." << std::endl; ``` ### function getFrameDroppedCount ```cpp unsigned int getFrameDroppedCount() ``` Returns the number of frames dropped since grab() was called for the first time. **Return**: The number of frames dropped since the first grab() call. 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). ### function getSVOPosition ```cpp int getSVOPosition() ``` Returns the current playback position in the SVO file. **See**: setSVOPosition() for an example. **Return**: The current frame position in the SVO file. Returns -1 if the SDK is not reading an SVO. **Note**: The method works only if the camera is open in SVO playback mode. 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). ### function getSVOPositionAtTimestamp ```cpp int getSVOPositionAtTimestamp( const sl::Timestamp & timestamp ) ``` Retrieves the frame index within the SVO file corresponding to the provided timestamp. **Parameters**: * **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. ### function setSVOPosition ```cpp sl::ERROR_CODE setSVOPosition( int position ) ``` Sets the playback cursor to the desired frame number in the SVO file. **Parameters**: * **position** : The position to set the SVO cursor to. **Return**: ERROR_CODE to indicate if the method was successful. **Note**: The method works only if the camera is open in SVO playback mode. **Warning**: Using this function is not a standard behavior as it creates a jump in time, backward or forward (which can not happen in live conditions). This function will then reset many modules such as positional tracking or spatial mapping. This method allows you to move around within a played-back SVO file. After calling, the next call to grab() will read the provided frame number. ```cpp #include using namespace sl; int main(int argc, char **argv) { // Create a ZED camera object Camera zed; // Set configuration parameters InitParameters init_params; init_params.input.setFromSVOFile("path/to/my/file.svo"); // Open the camera ERROR_CODE err = zed.open(init_params); if (err != ERROR_CODE::SUCCESS) { std::cout << toString(err) << std::endl; exit(-1); } // Loop between frames 0 and 50 Mat leftImage; while (zed.getSVOPosition() < zed.getSVONumberOfFrames() - 1) { std::cout << "Current frame: " << zed.getSVOPosition() << std::endl; // Loop if we reached frame 50 if (zed.getSVOPosition() == 50) zed.setSVOPosition(0); // Grab an image if (zed.grab() == ERROR_CODE::SUCCESS) { zed.retrieveImage(leftImage, VIEW::LEFT); // Get the rectified left image // Use the image in your application } } // Close the Camera zed.close(); return 0; } ``` ### function pauseSVOReading ```cpp void pauseSVOReading( bool status ) ``` Pauses or resumes SVO reading. **Parameters**: * **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 ### function getSVONumberOfFrames ```cpp int getSVONumberOfFrames() ``` Returns the number of frames in the SVO file. **See**: setSVOPosition() for an example. **Return**: The total number of frames in the SVO file. -1 if the SDK is not reading a SVO. **Note**: The method works only if the camera is open in SVO playback mode. ### function ingestDataIntoSVO ```cpp ERROR_CODE ingestDataIntoSVO( const sl::SVOData & data ) ``` Ingest SVOData in a SVO file. **Parameters**: * **data** : Data to ingest in the SVO file. **Return**: [sl::ERROR_CODE::SUCCESS] in case of success, [sl::ERROR_CODE::FAILURE] otherwise. **Note**: The method works only if the camera is recording. ### function retrieveSVOData ```cpp ERROR_CODE retrieveSVOData( const std::string & key, std::map< sl::Timestamp, sl::SVOData > & data, sl::Timestamp ts_begin =0, sl::Timestamp ts_end =0 ) ``` Retrieves SVO data from the SVO file at the given channel key and in the given timestamp range. **Parameters**: * **key** : The key of the SVOData that is going to be retrieved. * **data** : The map to be filled with SVOData objects, with timestamps as keys. * **ts_begin** : The beginning of the range. * **ts_end** : The end of the range. **Return**: [sl::ERROR_CODE::SUCCESS] in case of success, [sl::ERROR_CODE::FAILURE] otherwise. **Note**: The method works only if the camera is in SVO mode. ### function getSVODataKeys ```cpp std::vector< std::string > getSVODataKeys() ``` Get the external channels that can be retrieved from the SVO file. **Return**: List of available keys. **Note**: The method returns an empty std::vector if not in SVO mode. ### function retrieveMeasure ```cpp ERROR_CODE retrieveMeasure( Mat & mat, MEASURE measure =MEASURE::DEPTH, MEM type =MEM::CPU, Resolution image_size =Resolution(0, 0), cudaStream_t stream =0 ) ``` Computed measures, like depth, point cloud, or normals, can be retrieved using this method. **Parameters**: * **mat** : The Mat to store the measure. The method will create the Mat if necessary at the proper resolution. If already created, it will just update its data (CPU or GPU depending on the MEM type). * **measure** : Defines the measure you want (see MEASURE). Default: MEASURE::DEPTH. * **type** : Defines on which memory the image should be allocated. Default: MEM::CPU. * **image_size** : If specified, define the resolution of the output sl::Mat. If set to Resolution(0,0), the camera resolution or InitParameters::maximum_working_resolution will be taken, whichever is the smallest. Default: (0,0). 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 the function sl::setEnvironmentVariable("ZED_SDK_DISABLE_AUTO_RETRIEVE_RESOLUTION", "1") at the beginning of the code. * **stream** : If passed, the CUDA stream to use for GPU calls. **Return**: * ERROR_CODE::SUCCESS if the method succeeded. * ERROR_CODE::INVALID_FUNCTION_PARAMETERS if the view mode requires a module not enabled (VIEW::DEPTH with DEPTH_MODE::NONE for example). * ERROR_CODE::INVALID_RESOLUTION if the resolution is higher than one provided by getCameraInformation().camera_configuration.resolution. * ERROR_CODE::FAILURE if another error occurred. **Note**: * As this function retrieves the measures computed by the grab() function, This function should be called after a grab() call that returns ERROR_CODE::SUCCESS. * Measures containing "RIGHT" in their names, requires InitParameters::enable_right_side_measure to be enabled. **Warning**: A sl::Mat resolution higher than the camera resolution **cannot** be requested. 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 at the optimal resolution for speed and quality. However, custom resolutions can be requested. For example, requesting a higher measure for specific needs, or a lower resolution for even faster data transfer ```cpp Mat imageMap, depthMap, pointCloud; sl::Resolution resolution = zed.getCameraInformation().camera_configuration.resolution; int x = resolution.width / 2; // Center coordinates int y = resolution.height / 2; while (true) { if (zed.grab() == ERROR_CODE::SUCCESS) { // Grab an image zed.retrieveImage(imageMap, VIEW::LEFT); // Get the image if necessary zed.retrieveMeasure(depthMap, MEASURE::DEPTH, MEM::CPU); // Get the depth map // Read a depth value float centerDepth = 0; depthMap.getValue(x, y, ¢erDepth, MEM::CPU); // each depth map pixel is a float value if (std::isnormal(centerDepth)) { // + Inf is "too far", -Inf is "too close", Nan is "unknown/occlusion" std::cout << "Depth value at center: " << centerDepth << " " << init_params.coordinate_units << std::endl; } zed.retrieveMeasure(pointCloud, MEASURE::XYZBGRA, MEM::CPU);// Get the point cloud // Read a point cloud value sl::float4 pcValue; pointCloud.getValue(x, y, &pcValue); // each point cloud pixel contains 4 floats, so we are using a sl::float4 if (std::isnormal(pcValue.z)) { std::cout << "Point cloud coordinates at center: X=" << pcValue.x << ", Y=" << pcValue.y << ", Z=" << pcValue.z << std::endl; unsigned char color[sizeof(float)]; memcpy(color, &pcValue[3], sizeof(float)); std::cout << "Point cloud color at center: B=" << (int)color[0] << ", G=" << (int)color[1] << ", R=" << (int)color[2] << std::endl; } } } ``` ### function retrieveVoxelMeasure ```cpp ERROR_CODE retrieveVoxelMeasure( Mat & mat, MEASURE measure =MEASURE::XYZRGBA, MEM type =MEM::CPU, VoxelMeasureParameters params =VoxelMeasureParameters(), cudaStream_t stream =0 ) ``` Retrieves a voxel-decimated (downsampled) point cloud measure. **Parameters**: * **mat** : The Mat to store the decimated point cloud. Allocated once at maximum capacity and reused across frames. Use Mat::getWidth() to get the actual point count (the underlying buffer may be larger). * **measure** : The point cloud measure to retrieve. Default: MEASURE::XYZRGBA. * **type** : Memory type for the output. Default: MEM::CPU. * **params** : Voxel decimation parameters. See VoxelMeasureParameters. * **stream** : CUDA stream for GPU operations. **Return**: ERROR_CODE::SUCCESS if the method succeeded. **Note**: * Voxel positions are weighted by depth confidence, favoring more reliable points. * Internally, a stateful GPU downsampler is maintained per Camera instance for buffer reuse across frames. * As this function retrieves the measures computed by the grab() function, it should be called after a grab() call that returns ERROR_CODE::SUCCESS. Performs voxel grid decimation on the requested point cloud measure and returns the result as an unorganized 1D Mat with dimensions (N, 1) where N is the number of output points. Use Mat::getWidth() to get the output point count. Only point cloud measures are supported: MEASURE::XYZ, MEASURE::XYZRGBA, MEASURE::XYZBGRA, MEASURE::XYZARGB, MEASURE::XYZABGR (and their RIGHT variants). Returns ERROR_CODE::INVALID_FUNCTION_PARAMETERS for non-point-cloud measures. ### function setRegionOfInterest ```cpp ERROR_CODE setRegionOfInterest( sl::Mat & roi_mask, std::unordered_set< MODULE > module ={MODULE::ALL} ) ``` Defines a region of interest to focus on for all the SDK, discarding other parts. **Parameters**: * **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. * **module** Apply the ROI to a list of SDK module, all by default **Return**: An ERROR_CODE if something went wrong. **Note**: The method support U8_C1/U8_C3/U8_C4 images type. ### function getRegionOfInterest ```cpp ERROR_CODE getRegionOfInterest( sl::Mat & roi_mask, sl::Resolution image_size =Resolution(0, 0), MODULE module =MODULE::ALL ) ``` Get the previously set or computed region of interest. **Parameters**: * **roi_mask** The Mat returned * **image_size** The optional size of the returned mask * **module** specify which module to get the ROI **Return**: An ERROR_CODE if something went wrong. ### function startRegionOfInterestAutoDetection ```cpp ERROR_CODE startRegionOfInterestAutoDetection( sl::RegionOfInterestParameters roi_param =sl::RegionOfInterestParameters() ) ``` 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. **Parameters**: * **roi_param** The RegionOfInterestParameters defining parameters for the detection **Return**: An ERROR_CODE if something went wrong. **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 getRegionOfInterestAutoDetectionStatus(), the result is either auto applied, or can be retrieve using getRegionOfInterest function. ### function getRegionOfInterestAutoDetectionStatus ```cpp REGION_OF_INTEREST_AUTO_DETECTION_STATE getRegionOfInterestAutoDetectionStatus() ``` 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 ### function getCurrentMinMaxDepth ```cpp ERROR_CODE getCurrentMinMaxDepth( float & min, float & max ) ``` Gets the current range of perceived depth. **Parameters**: * **min** : Minimum depth detected (in selected sl::UNIT). * **max** : Maximum depth detected (in selected sl::UNIT). **Return**: ERROR_CODE::SUCCESS if values can be extracted, ERROR_CODE::FAILURE otherwise. ### function enablePositionalTracking ```cpp ERROR_CODE enablePositionalTracking( PositionalTrackingParameters tracking_parameters =PositionalTrackingParameters() ) ``` Initializes and starts the positional tracking processes. **Parameters**: * **tracking_parameters** : 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. 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 parameter can be set by providing PositionalTrackingParameters to this method. ```cpp #include using namespace sl; int main(int argc, char **argv) { // --- Initialize a Camera object and open the ZED // Create a ZED camera object Camera zed; // Set configuration parameters InitParameters init_params; init_params.camera_resolution = RESOLUTION::HD720; // Use HD720 video mode init_params.camera_fps = 60; // Set fps at 60 // Open the camera ERROR_CODE err = zed.open(init_params); if (err != ERROR_CODE::SUCCESS) { std::cout << toString(err) << std::endl; exit(-1); } // Set tracking parameters PositionalTrackingParameters track_params; track_params.enable_area_memory = true; // Enable positional tracking err = zed.enablePositionalTracking(track_params); if (err != ERROR_CODE::SUCCESS) { std::cout << "Tracking error: " << toString(err) << std::endl; exit(-1); } // --- Main loop while (true) { if (zed.grab() == ERROR_CODE::SUCCESS) { // Grab an image and computes the tracking Pose cameraPose; zed.getPosition(cameraPose, REFERENCE_FRAME::WORLD); std::cout << "Camera position: X=" << cameraPose.getTranslation().x << " Y=" << cameraPose.getTranslation().y << " Z=" << cameraPose.getTranslation().z << std::endl; } } // --- Close the Camera zed.close(); return 0; } ``` ### function getPosition ```cpp POSITIONAL_TRACKING_STATE getPosition( Pose & camera_pose, REFERENCE_FRAME reference_frame =REFERENCE_FRAME::WORLD ) ``` Retrieves the estimated position and orientation of the camera in the specified reference frame. **Parameters**: * **camera_pose** : The pose containing the position of the camera and other information (timestamp, confidence). * **reference_frame** : Defines the reference from which you want the pose to be expressed. Default: REFERENCE_FRAME::WORLD. **Return**: The current state of the tracking process. **Note**: * Extract Rotation Matrix: Pose.getRotationMatrix() * Extract Translation Vector: Pose.getTranslation() * Extract Orientation / Quaternion: Pose.getOrientation() * The position is provided in the InitParameters::coordinate_system . See COORDINATE_SYSTEM for its physical origin. **Warning**: This method requires the tracking to be enabled. enablePositionalTracking() . * 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. ```cpp // --- Main loop while (true) { if (zed.grab() == ERROR_CODE::SUCCESS) { // Grab an image and computes the tracking Pose cameraPose; zed.getPosition(cameraPose, REFERENCE_FRAME::WORLD); std::cout << "Camera position: X=" << cameraPose.getTranslation().x << " Y=" << cameraPose.getTranslation().y << " Z=" << cameraPose.getTranslation().z << std::endl; std::cout << "Camera Euler rotation: X=" << cameraPose.getEulerAngles().x << " Y=" << cameraPose.getEulerAngles().y << " Z=" << cameraPose.getEulerAngles().z << std::endl; std::cout << "Camera Rodrigues rotation: X=" << cameraPose.getRotationVector().x << " Y=" << cameraPose.getRotationVector().y << " Z=" << cameraPose.getRotationVector().z << std::endl; std::cout << "Camera quaternion orientation: X=" << cameraPose.getOrientation().x << " Y=" << cameraPose.getOrientation().y << " Z=" << cameraPose.getOrientation().z << " W=" << cameraPose.getOrientation().w << std::endl; std::cout << std::endl; } } ``` ### function getPositionalTrackingLandmarks ```cpp sl::ERROR_CODE getPositionalTrackingLandmarks( std::map< uint64_t, sl::Landmark > & landmarks ) ``` Get the current positional tracking landmarks. **Parameters**: * **landmarks** Dictionnary of presents landmarks. The key is the unique ID of the landmark and the value is the landmark itself. **Return**: ERROR_CODE that indicate if the function succeed or not. ### function getPositionalTrackingLandmarks2D ```cpp sl::ERROR_CODE getPositionalTrackingLandmarks2D( std::vector< sl::Landmark2D > & current_2d_landmarks ) ``` Get the feature tracked by the positional tracking in the current image. **Parameters**: * **current_2d_landmarks** A vector containing the coordinates of the feature being tracked. **Return**: ERROR_CODE that indicate if the function succeed or not. ### function getPositionalTrackingKeyframes ```cpp sl::ERROR_CODE getPositionalTrackingKeyframes( std::map< uint64_t, sl::KeyFrame > & keyframes ) ``` Get the Keyframe currenlty used by the positional tracking. **Parameters**: * **keyframes** Dictionnary of presents keyframes. The key is the unique ID of the keyframe and the value is the keyframe itself. **Return**: ERROR_CODE that indicate if the function succeed or not. ### function getPositionalTrackingStatus ```cpp sl::PositionalTrackingStatus getPositionalTrackingStatus() ``` Return the current status of positional tracking module. **Return**: sl::PositionalTrackingStatus current status of positional tracking module. ### function saveAreaMap ```cpp ERROR_CODE saveAreaMap( String area_file_path ) ``` Saves the current area learning file. The file will contain spatial memory data generated by the tracking. **Parameters**: * **area_file_path** : Path of an '.area' file to save the spatial memory database in. **See**: getAreaExportState() **Return**: ERROR_CODE::FAILURE if the **area_file_path** file wasn't found, ERROR_CODE::SUCCESS otherwise. **Note**: This method is asynchronous because the generated data can be heavy, be sure to loop over the getAreaExportState() method with a waiting time. **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. * The getAreaExportState() method will return AREA_EXPORTING_STATE::FILE_EMPTY. * A few meters (~3m) of translation or a full rotation should be enough to get usable spatial memory. * However, as it should be used for relocation purposes, visiting a significant portion of the environment is recommended before exporting. 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 getAreaExportState() to get the export state. The positional tracking keeps running while exporting. ```cpp // --- Main loop while (true) { if (zed.grab() == SUCCESS) { // Grab an image and computes the tracking Pose cameraPose; zed.getPosition(cameraPose, REFERENCE_FRAME::WORLD); } } // Export the spatial memory for future sessions zed.saveAreaMap("MyMap.area"); auto export_state = sl::AREA_EXPORTING_STATE::RUNNING; while (export_state == sl::AREA_EXPORTING_STATE::RUNNING) { export_state = zed.getAreaExportState(); sl::sleep_ms(5); } std::cout << "export state: " << export_state << std::endl; // --- Close the Camera zed.close(); // The close method will wait for the end of the file creation using getAreaExportState(). return 0; ``` ### function getAreaExportState ```cpp AREA_EXPORTING_STATE getAreaExportState() ``` Returns the state of the spatial memory export process. **Return**: The current state of the spatial memory export process. As saveAreaMap() only starts the exportation, this method allows you to know when the exportation finished or if it failed. ### function resetPositionalTracking ```cpp ERROR_CODE resetPositionalTracking( const Transform & path ) ``` Resets the tracking, and re-initializes the position with the given transformation matrix. **Parameters**: * **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. * Please note that this method is not meant to be used in parallel of the grab() method. ### function disablePositionalTracking ```cpp void disablePositionalTracking( String area_file_path ="" ) ``` Disables the positional tracking. **Parameters**: * **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"_. **Note**: The '.area' database depends on the depth mode and confidence threshold chosen during the recording. The same mode must be used to reload the database. The positional tracking is immediately stopped. If a file path is given, saveAreaMap() will be called asynchronously. See getAreaExportState() to get the exportation state. If the tracking has been enabled, this function will automatically be called by close() . ### function isPositionalTrackingEnabled ```cpp bool isPositionalTrackingEnabled() ``` Tells if the tracking module is enabled. ### function getPositionalTrackingParameters ```cpp PositionalTrackingParameters getPositionalTrackingParameters() const ``` Returns the PositionalTrackingParameters used. **Return**: PositionalTrackingParameters containing the parameters used for positional tracking initialization. It corresponds to the structure given as argument to the enablePositionalTracking() method. ### function getSensorsData ```cpp ERROR_CODE getSensorsData( SensorsData & data, TIME_REFERENCE reference_time ) ``` Retrieves the SensorsData (IMU, magnetometer, barometer) at a specific time reference. **Parameters**: * **data** : The SensorsData variable to store the data. * **reference_time** Defines the reference from which you want the data to be expressed. **Return**: * ERROR_CODE::SUCCESS if sensors data have been extracted. * ERROR_CODE::SENSORS_NOT_AVAILABLE if the camera model is a MODEL::ZED. * ERROR_CODE::MOTION_SENSORS_REQUIRED if the camera model is correct but the sensors module is not opened. * ERROR_CODE::INVALID_FUNCTION_PARAMETERS if the **reference_time** is not valid. See Warning. **Note**: The IMU quaternion (fused data) is given in the specified COORDINATE_SYSTEM of InitParameters. * Calling getSensorsData with TIME_REFERENCE::CURRENT gives you the latest sensors data received. Getting all the data requires to call this method at high frame rate in a thread. * Calling getSensorsData with TIME_REFERENCE::IMAGE gives you the sensors data at the time of the latest image grabbed. SensorsData object contains the previous SensorsData::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: * data.imu.pose * **Raw values** from the IMU sensor: * data.imu.angular_velocity, corresponding to the gyroscope * data.imu.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` ```cpp if (zed.getSensorsData(sensors_data, TIME_REFERENCE::CURRENT) == ERROR_CODE::SUCCESS) { std::cout << " - IMU:\n"; std::cout << " \t Orientation: {" << sensors_data.imu.pose.getOrientation() << "}\n"; std::cout << " \t Acceleration: {" << sensors_data.imu.linear_acceleration << "} [m/sec^2]\n"; std::cout << " \t Angular Velocity: {" << sensors_data.imu.angular_velocity << "} [deg/sec]\n"; std::cout << " - Magnetometer\n \t Magnetic Field: {" << sensors_data.magnetometer.magnetic_field_calibrated << "} [uT]\n"; std::cout << " - Barometer\n \t Atmospheric pressure:" << sensors_data.barometer.pressure << " [hPa]\n"; // retrieves camera sensors temperature std::cout << " - Temperature\n"; float temperature; for (int s = 0; s < static_cast(SensorsData::TemperatureData::SENSOR_LOCATION::LAST); s++) { auto sensor_loc = static_cast(s); // depending on your Camera model or its firmware, different sensors can give thermal information if (sensors_data.temperature.get(sensor_loc, temperature) == ERROR_CODE::SUCCESS) std::cout << " \t " << sensor_loc << ": " << temperature << "C\n"; } } ``` ### function getSensorsDataBatch ```cpp ERROR_CODE getSensorsDataBatch( std::vector< SensorsData > & data ) ``` 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: **Parameters**: * **data** : The SensorsData vector to store the data. **Return**: * ERROR_CODE::SUCCESS if sensors data have been extracted. * ERROR_CODE::SENSORS_NOT_AVAILABLE if the camera model is a MODEL::ZED. * ERROR_CODE::MOTION_SENSORS_REQUIRED if the camera model is correct but the sensors module is not opened. * ERROR_CODE::INVALID_FUNCTION_PARAMETERS if the **reference_time** is not valid. See Warning. * **Time-fused** pose estimation that can be accessed using: * data.imu.pose * **Raw values** from the IMU sensor: * data.imu.angular_velocity, corresponding to the gyroscope * data.imu.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` ```cpp if (zed.grab() == ERROR_CODE::SUCCESS) { std::vector sensors_data; if (zed.getSensorsDataBatch(sensors_data) == ERROR_CODE::SUCCESS) { for (const auto& sensor_data : sensors_data) { std::cout << " - IMU:\n"; std::cout << " \t Orientation: {" << sensor_data.imu.pose.getOrientation() << "}\n"; std::cout << " \t Acceleration: {" << sensor_data.imu.linear_acceleration << "} [m/sec^2]\n"; std::cout << " \t Angular Velocity: {" << sensor_data.imu.angular_velocity << "} [deg/sec]\n"; } } } ``` ### function setIMUPrior ```cpp ERROR_CODE setIMUPrior( const sl::Transform & transform ) ``` Set an optional IMU orientation hint that will be used to assist the tracking during the next grab(). **Parameters**: * **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). **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. This method can be used to assist the positional tracking rotation. ### function enableSpatialMapping ```cpp ERROR_CODE enableSpatialMapping( SpatialMappingParameters spatial_mapping_parameters =SpatialMappingParameters() ) ``` Initializes and starts the spatial mapping processes. **Parameters**: * **spatial_mapping_parameters** : 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. **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. **Warning**: * The tracking (enablePositionalTracking() ) and the depth (RuntimeParameters::enable_depth ) needs to be enabled to use the spatial mapping. * The performance greatly depends on the **spatial_mapping_parameters**. * 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. 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 extractWholeSpatialMap() or retrieveSpatialMapAsync(). Note that retrieveSpatialMapAsync() should be called after requestSpatialMapAsync(). ```cpp #include using namespace sl; int main(int argc, char **argv) { // Create a ZED camera object Camera zed; // Set initial parameters InitParameters init_params; init_params.camera_resolution = RESOLUTION::HD720; // Use HD720 video mode (default fps: 60) init_params.coordinate_system = COORDINATE_SYSTEM::RIGHT_HANDED_Y_UP; // Use a right-handed Y-up coordinate system (The OpenGL one) init_params.coordinate_units = UNIT::METER; // Set units in meters // Open the camera ERROR_CODE err = zed.open(init_params); if (err != ERROR_CODE::SUCCESS) exit(-1); // Positional tracking needs to be enabled before using spatial mapping sl::PositionalTrackingParameters tracking_parameters; err = zed.enablePositionalTracking(tracking_parameters); if (err != ERROR_CODE::SUCCESS) exit(-1); // Enable spatial mapping sl::SpatialMappingParameters mapping_parameters; err = zed.enableSpatialMapping(mapping_parameters); if (err != ERROR_CODE::SUCCESS) exit(-1); // Grab data during 500 frames int i = 0; sl::Mesh mesh; // Create a mesh object while (i < 500) { // For each new grab, mesh data is updated if (zed.grab() == ERROR_CODE::SUCCESS) { // In the background, the spatial mapping will use newly retrieved images, depth and pose to update the mesh sl::SPATIAL_MAPPING_STATE mapping_state = zed.getSpatialMappingState(); // Print spatial mapping state std::cout << "Images captured: " << i << " / 500 || Spatial mapping state: " << mapping_state << std::endl; i++; } } std::cout << std::endl; // Extract, filter and save the mesh in a obj file std::cout << "Extracting Mesh ..." << std::endl; zed.extractWholeSpatialMap(mesh); // Extract the whole mesh std::cout << "Filtering Mesh ..." << std::endl; mesh.filter(sl::MeshFilterParameters::MESH_FILTER::LOW); // Filter the mesh (remove unnecessary vertices and faces) std::cout << "Saving Mesh in mesh.obj ..." << std::endl; mesh.save("mesh.obj"); // Save the mesh in an obj file // Disable tracking and mapping and close the camera zed.disableSpatialMapping(); zed.disablePositionalTracking(); zed.close(); return 0; } ``` ### function getSpatialMappingState ```cpp SPATIAL_MAPPING_STATE getSpatialMappingState() ``` Returns the current spatial mapping state. **See**: SPATIAL_MAPPING_STATE **Return**: The current state of the spatial mapping process. As the spatial mapping runs asynchronously, this method allows you to get reported errors or status info. ### function requestSpatialMapAsync ```cpp void requestSpatialMapAsync() ``` Starts the spatial map generation process in a non-blocking thread from the spatial mapping process. **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. 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 getSpatialMapRequestStatusAsync(), and retrieve the mesh using retrieveSpatialMapAsync() . See enableSpatialMapping() for an example. ### function getSpatialMapRequestStatusAsync ```cpp ERROR_CODE getSpatialMapRequestStatusAsync() ``` Returns the spatial map generation status. **Return**: ERROR_CODE::SUCCESS if the mesh is ready and not yet retrieved, otherwise ERROR_CODE::FAILURE. This status allows to know if the mesh can be retrieved by calling retrieveSpatialMapAsync . See enableSpatialMapping() for an example. ### function retrieveSpatialMapAsync ```cpp ERROR_CODE retrieveSpatialMapAsync( Mesh & mesh ) ``` Retrieves the current generated spatial map only if SpatialMappingParameters::map_type was set as MESH. **Parameters**: * **mesh** : The mesh to be filled with the generated spatial map. **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 between two calls of this method, otherwise it can lead to a corrupted mesh. * If the SpatialMappingParameters::map_type has not been setup as MESH, the object will be empty. After calling requestSpatialMapAsync(), this method allows you to retrieve the generated mesh. The mesh will only be available when getSpatialMapRequestStatusAsync() returns ERROR_CODE::SUCCESS. See enableSpatialMapping() for an example. ### function retrieveSpatialMapAsync ```cpp ERROR_CODE retrieveSpatialMapAsync( FusedPointCloud & fpc ) ``` Retrieves the current generated spatial map only if SpatialMappingParameters::map_type was set as FUSED_POINT_CLOUD. **Parameters**: * **fpc** : The fused point cloud to be filled with the generated spatial map. **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 fused point cloud between two calls of this method, otherwise it can lead to a corrupted fused point cloud. * If the SpatialMappingParameters::map_type has not been setup as FUSED_POINT_CLOUD, the object will be empty. After calling requestSpatialMapAsync(), this method allows you to retrieve the generated fused point cloud. The fused point cloud will only be available when getSpatialMapRequestStatusAsync() returns ERROR_CODE::SUCCESS. See enableSpatialMapping() for an example. ### function extractWholeSpatialMap ```cpp ERROR_CODE extractWholeSpatialMap( Mesh & mesh ) ``` Extract the current spatial map from the spatial mapping process only if SpatialMappingParameters::map_type was set as MESH. **Parameters**: * **mesh** : The mesh to be filled with the generated spatial map. **Return**: ERROR_CODE::SUCCESS if the mesh is filled and available, otherwise ERROR_CODE::FAILURE. **Warning**: * This is a blocking method. You should either call it in a thread or at the end of the mapping process. The extraction can be long, calling this method in the grab loop will block the depth and tracking computation giving bad results. * If the SpatialMappingParameters::map_type has not been setup as MESH, the object will be empty. If the object to be filled already contains a previous version of the mesh, only changes will be updated, optimizing performance. See enableSpatialMapping() for an example. ### function extractWholeSpatialMap ```cpp ERROR_CODE extractWholeSpatialMap( FusedPointCloud & fpc ) ``` Extract the current spatial map from the spatial mapping process only if SpatialMappingParameters::map_type was set as FUSED_POINT_CLOUD. **Parameters**: * **fpc** : The fused point cloud to be filled with the generated spatial map. **Return**: ERROR_CODE::SUCCESS if the fused point cloud is filled and available, otherwise ERROR_CODE::FAILURE. **Warning**: * This is a blocking method. You should either call it in a thread or at the end of the mapping process. The extraction can be long, calling this method in the grab loop will block the depth and tracking computation giving bad results. * If the SpatialMappingParameters::map_type has not been setup as FUSED_POINT_CLOUD, the object will be empty. If the object to be filled already contains a previous version of the fused point cloud, only changes will be updated, optimizing performance. See enableSpatialMapping() for an example. ### function pauseSpatialMapping ```cpp void pauseSpatialMapping( bool status ) ``` Pauses or resumes the spatial mapping processes. **Parameters**: * **status** : If true, the integration is paused. If false, the spatial mapping is resumed. 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. ### function disableSpatialMapping ```cpp void disableSpatialMapping() ``` Disables the spatial mapping process. **Note**: This method frees the memory allocated for the spatial mapping, consequently, meshes and fused point clouds cannot be retrieved after this call. The spatial mapping is immediately stopped. If the mapping has been enabled, this method will automatically be called by close(). ### function getSpatialMappingParameters ```cpp SpatialMappingParameters getSpatialMappingParameters() const ``` Returns the SpatialMappingParameters used. **Return**: SpatialMappingParameters containing the parameters used for spatial mapping initialization. It corresponds to the structure given as argument to the enableSpatialMapping() method. ### function enableRecording ```cpp ERROR_CODE enableRecording( RecordingParameters recording_parameters ) ``` Creates an SVO file to be filled by enableRecording() and disableRecording(). **Parameters**: * **recording_parameters** : 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. 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. ```cpp #include using namespace sl; int main(int argc, char **argv) { // Create a ZED camera object Camera zed; // Set initial parameters InitParameters init_params; init_params.camera_resolution = RESOLUTION::HD720; // Use HD720 video mode (default fps: 60) init_params.coordinate_units = UNIT::METER; // Set units in meters // Open the camera ERROR_CODE err = zed.open(init_params); if (err != ERROR_CODE::SUCCESS) { std::cout << toString(err) << std::endl; exit(-1); } // Enable video recording err = zed.enableRecording(RecordingParameters("myVideoFile.svo", SVO_COMPRESSION_MODE::H265)); if (err != ERROR_CODE::SUCCESS) { std::cout << toString(err) << std::endl; exit(-1); } // Grab data during 500 frames int i = 0; while (i < 500) { // Grab a new frame if (zed.grab() == ERROR_CODE::SUCCESS) { // Record the grabbed frame in the video file i++; } } zed.disableRecording(); std::cout << "Video has been saved ..." << std::endl; zed.close(); return 0; } ``` ### function getRecordingStatus ```cpp RecordingStatus getRecordingStatus() ``` Get the recording information. **Return**: The recording state structure. For more details, see RecordingStatus. ### function pauseRecording ```cpp void pauseRecording( bool status ) ``` Pauses or resumes the recording. **Parameters**: * **status** : If true, the recording is paused. If false, the recording is resumed. ### function disableRecording ```cpp void disableRecording() ``` Disables the recording initiated by enableRecording() and closes the generated file. **Note**: This method will automatically be called by close() if enableRecording() was called. See enableRecording() for an example. ### function getRecordingParameters ```cpp RecordingParameters getRecordingParameters() const ``` Returns the RecordingParameters used. **Return**: RecordingParameters containing the parameters used for recording initialization. It corresponds to the structure given as argument to the enableRecording() method. ### function enableStreaming ```cpp ERROR_CODE enableStreaming( StreamingParameters streaming_parameters =StreamingParameters() ) ``` Creates a streaming pipeline. **Parameters**: * **streaming_parameters** : A structure containing all the specific parameters for the streaming. Default: a reset of StreamingParameters . **Return**: * ERROR_CODE::SUCCESS if streaming was successfully started. * ERROR_CODE::INVALID_FUNCTION_CALL if open() was not successfully called before. * ERROR_CODE::FAILURE if streaming RTSP protocol was not able to start. * ERROR_CODE::NO_GPU_COMPATIBLE if streaming codec is not supported (in this case, use H264 codec which is supported on all NVIDIA GPU the ZED SDK supports). ```cpp #include using namespace sl; int main(int argc, char **argv) { // Create a ZED camera object Camera zed; // Open the camera ERROR_CODE err = zed.open(); if (err != ERROR_CODE::SUCCESS) { std::cout << toString(err) << std::endl; exit(-1); } // Enable video recording sl::StreamingParameters stream_params; err = zed.enableStreaming(stream_params); if (err != ERROR_CODE::SUCCESS) { std::cout << toString(err) << std::endl; exit(-1); } // Grab data during 500 frames int i = 0; while (i < 500) { // Grab a new frame if (zed.grab() == ERROR_CODE::SUCCESS) i++; } zed.disableStreaming(); zed.close(); return 0; } ``` ### function disableStreaming ```cpp void disableStreaming() ``` Disables the streaming initiated by enableStreaming(). **Note**: This method will automatically be called by close() if enableStreaming() was called. See enableStreaming() for an example. ### function isStreamingEnabled ```cpp bool isStreamingEnabled() ``` Tells if the streaming is running. **Return**: true if the stream is running, false otherwise. ### function getStreamingParameters ```cpp StreamingParameters getStreamingParameters() const ``` Returns the StreamingParameters used. **Return**: StreamingParameters containing the parameters used for streaming initialization. It corresponds to the structure given as argument to the enableStreaming() method. ### function enableObjectDetection ```cpp ERROR_CODE enableObjectDetection( ObjectDetectionParameters object_detection_parameters =ObjectDetectionParameters() ) ``` Initializes and starts object detection module. **Parameters**: * **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. * ERROR_CODE::CORRUPTED_SDK_INSTALLATION if the AI model is missing or corrupted. In this case, the SDK needs to be reinstalled. * ERROR_CODE::MODULE_NOT_COMPATIBLE_WITH_CAMERA if the camera used does not have a IMU (MODEL::ZED). * ERROR_CODE::MOTION_SENSORS_REQUIRED 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. * 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). * ERROR_CODE::FAILURE otherwise. **Note**: * - **This Depth Learning detection module is not available MODEL::ZED cameras**. * - This feature uses AI to locate objects and requires a powerful GPU. A GPU with at least 3GB of memory is recommended. * 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 camera model. 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 retrieveObjects() 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 retrieveCustomObjects() method. ```cpp #include using namespace sl; int main(int argc, char **argv) { // Create a ZED camera object Camera zed; // Open the camera ERROR_CODE err = zed.open(); if (err != ERROR_CODE::SUCCESS) { std::cout << "Opening camera error: " << toString(err) << std::endl; exit(-1); } // Enable position tracking (mandatory for object detection) PositionalTrackingParameters tracking_params; err = zed.enablePositionalTracking(tracking_params); if (err != ERROR_CODE::SUCCESS) { std::cout << "Enabling Positional Tracking error: " << toString(err) << std::endl; exit(-1); } // Set the object detection parameters ObjectDetectionParameters object_detection_params; // Enable the object detection err = zed.enableObjectDetection(object_detection_params); if (err != ERROR_CODE::SUCCESS) { std::cout << "Enabling Object Detection error: " << toString(err) << std::endl; exit(-1); } // Grab an image and detect objects on it Objects objects; while (true) { if (zed.grab() == ERROR_CODE::SUCCESS) { zed.retrieveObjects(objects); std::cout << objects.object_list.size() << " objects detected " << std::endl; // Use the objects in your application } } // Close the Camera zed.disableObjectDetection(); zed.close(); return 0; } ``` ### function disableObjectDetection ```cpp void disableObjectDetection( unsigned int instance_id =0, bool force_disable_all_instances =false ) ``` Disables the Object Detection process. **Parameters**: * **instance_id** : Id of the object detection instance. Used when multiple instances of the object detection module are enabled at the same time. * **force_disable_all_instances** : Should disable all instances of the object detection module or just **instance_id**. **Note**: If the object detection has been enabled, this method will automatically be called by close(). The object detection module immediately stops and frees its memory allocations. ### function ingestCustomBoxObjects ```cpp ERROR_CODE ingestCustomBoxObjects( const std::vector< CustomBoxObjectData > & objects_in, const unsigned int instance_id =0 ) ``` Feed the 3D Object tracking method with your own 2D bounding boxes from your own detection algorithm. **Parameters**: * **objects_in** : Vector of CustomBoxObjectData to feed the object detection. * **instance_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 informations and perform object tracking. ### function ingestCustomMaskObjects ```cpp ERROR_CODE ingestCustomMaskObjects( const std::vector< CustomMaskObjectData > & objects_in, const unsigned int instance_id =0 ) ``` Feed the 3D Object tracking method with your own 2D bounding boxes with masks from your own detection algorithm. **Parameters**: * **objects_in** : Vector of CustomMaskObjectData to feed the object detection. * **instance_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 informations and perform object tracking. ### function setObjectDetectionRuntimeParameters ```cpp ERROR_CODE setObjectDetectionRuntimeParameters( const ObjectDetectionRuntimeParameters & params, const unsigned int instance_id =0 ) ``` Set the Object detection module instance runtime parameters By default the object detection module will use the parameters set in the ObjectDetectionRuntimeParameters constructor. This can be changed at any time, however since the processing is done in parallel, the parameters will be used for the next inference. This function can be called only on parameters change, the previous values will be applied during inference. **Parameters**: * **params** : ObjectDetectionRuntimeParameters parameters * **instance_id** : Object detection instance id, by default the first instance ### function setCustomObjectDetectionRuntimeParameters ```cpp ERROR_CODE setCustomObjectDetectionRuntimeParameters( const CustomObjectDetectionRuntimeParameters & params, const unsigned int instance_id =0 ) ``` Set the Object detection module instance runtime parameters when using the Custom model ([OBJECT_DETECTION_MODEL::CUSTOM_BOX_OBJECTS] and CUSTOM_BOX_OBJECTS::CUSTOM_YOLOLIKE_BOX_OBJECTS) By default the object detection module will use the parameters set in the CustomObjectDetectionRuntimeParameters constructor. This can be changed at any time, however since the processing is done in parallel, the parameters will be used for the next inference. This function can be called only on parameters change, the previous values will be applied during inference. **Parameters**: * **params** : CustomObjectDetectionRuntimeParameters parameters * **instance_id** : Object detection instance id, by default the first instance ### function retrieveObjects ```cpp ERROR_CODE retrieveObjects( Objects & objects, const unsigned int instance_id =0 ) ``` Retrieve objects detected by the object detection module. **Parameters**: * **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. * **instance_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. This method returns the result of the object detection, 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. 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. ```cpp Objects objects; // Unique Objects to be updated after each grab // --- Main loop while (true) { if (zed.grab() == ERROR_CODE::SUCCESS) { // Grab an image from the camera zed.retrieveObjects(objects); for (auto object : objects.object_list) { std::cout << object.label << std::endl; } } } ``` ### function retrieveObjects ```cpp ERROR_CODE retrieveObjects( Objects & objects, ObjectDetectionRuntimeParameters parameters, const unsigned int instance_id =0 ) ``` Retrieve objects detected by the object detection module. **Parameters**: * **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. * **parameters** : Object detection runtime settings, can be changed at each detection. In async mode, the parameters update is applied on the next iteration. * **instance_id** : Id of the object detection instance. Used when multiple instances of the object detection module are enabled at the same time. **Deprecated**: setObjectDetectionRuntimeParameters and retrieveObjects(Objects &objects, const unsigned int instance_id) methods should be used instead **Return**: ERROR_CODE::SUCCESS if everything went fine, ERROR_CODE::FAILURE otherwise. This method returns the result of the object detection, 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. 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. ```cpp Objects objects; // Unique Objects to be updated after each grab // --- Main loop while (true) { if (zed.grab() == ERROR_CODE::SUCCESS) { // Grab an image from the camera zed.retrieveObjects(objects); for (auto object : objects.object_list) { std::cout << object.label << std::endl; } } } ``` ### function retrieveCustomObjects ```cpp ERROR_CODE retrieveCustomObjects( Objects & objects, CustomObjectDetectionRuntimeParameters parameters, const unsigned int instance_id =0 ) ``` Retrieve custom objects detected by the object detection module. **Parameters**: * **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. * **parameters** : Custom object detection runtime settings, can be changed at each detection. In async mode, the parameters update is applied on the next iteration. * **instance_id** : Id of the object detection instance. Used when multiple instances of the object detection module are enabled at the same time. **Deprecated**: setCustomObjectDetectionRuntimeParameters and retrieveObjects(Objects &objects, const unsigned int instance_id) methods should be used instead **Return**: ERROR_CODE::SUCCESS if everything went fine, ERROR_CODE::FAILURE otherwise. If the object detection module is initialized with OBJECT_DETECTION_MODEL::CUSTOM_BOX_OBJECTS, the objects retrieved will be the ones from ingestCustomBoxObjects or ingestCustomMaskObjects. 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, 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. 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. ```cpp Objects objects; // Unique Objects to be updated after each grab // --- Main loop while (true) { if (zed.grab() == ERROR_CODE::SUCCESS) { // Grab an image from the camera zed.retrieveCustomObjects(objects); for (auto object : objects.object_list) { std::cout << object.label << std::endl; } } } ``` ### function getObjectsBatch ```cpp ERROR_CODE getObjectsBatch( std::vector< sl::ObjectsBatch > & trajectories, unsigned int instance_id =0 ) ``` Get a batch of detected objects. **Parameters**: * **trajectories** as a std::vector of sl::ObjectsBatch, that will be filled by the batching queue process. * **instance_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::INVALID_FUNCTION_CALL if batching module is not available or if object tracking was not enabled. **Note**: Most of the time, the vector will be empty and will be filled every BatchParameters::latency. **Warning**: This method need to be called after retrieveObjects, otherwise trajectories will be empty. It is the retrieveObjects method that ingest the current/live objects into the batching queue. ```cpp Objects objects; // Unique Objects to be updated after each grab // --- Main loop while (true) { if (zed.grab() == ERROR_CODE::SUCCESS) { // Grab an image from the camera //Call retrieveObjects so that objects are ingested in the batching system zed.retrieveObjects(objects); // Get batch of objects std::vector traj_; zed.getObjectsBatch(traj_); std::cout<<" Size of batch: "< using namespace sl; int main(int argc, char **argv) { // Create a ZED camera object Camera zed; // Open the camera ERROR_CODE err = zed.open(); if (err != ERROR_CODE::SUCCESS) { std::cout << "Opening camera error: " << toString(err) << std::endl; exit(-1); } // Enable position tracking (mandatory for body tracking) PositionalTrackingParameters tracking_params; err = zed.enablePositionalTracking(tracking_params); if (err != ERROR_CODE::SUCCESS) { std::cout << "Enabling Positional Tracking error: " << toString(err) << std::endl; exit(-1); } // Set the body tracking parameters BodyTrackingParameters body_tracking_params; // Enable the body tracking err = zed.enableBodyTracking(body_tracking_params); if (err != ERROR_CODE::SUCCESS) { std::cout << "Enabling Body Tracking error: " << toString(err) << std::endl; exit(-1); } // Grab an image and detect bodies on it Bodies bodies; while (true) { if (zed.grab() == ERROR_CODE::SUCCESS) { zed.retrieveBodies(bodies); std::cout << bodies.body_list.size() << " bodies detected " << std::endl; // Use the bodies in your application } } // Close the Camera zed.disableBodyTracking(); zed.close(); return 0; } ``` ### function disableBodyTracking ```cpp void disableBodyTracking( unsigned int instance_id =0, bool force_disable_all_instances =false ) ``` Disables the body tracking process. **Parameters**: * **instance_id** : Id of the body tracking instance. Used when multiple instances of the body tracking module are enabled at the same time. * **force_disable_all_instances** : Should disable all instances of the tracking module module or just **instance_id**. **Note**: If the body tracking has been enabled, this method will automatically be called by close(). The body tracking module immediately stops and frees its memory allocations. ### function setBodyTrackingRuntimeParameters ```cpp ERROR_CODE setBodyTrackingRuntimeParameters( const BodyTrackingRuntimeParameters & params, const unsigned int instance_id =0 ) ``` Set the Body tracking module instance runtime parameters By default the Body tracking module will use the parameters set in the BodyTrackingRuntimeParameters constructor. This can be changed at any time, however since the processing is done in parallel, the parameters will be used for the next inference. This function can be called only on parameters change, the previous values will be applied during inference. **Parameters**: * **params** : BodyTrackingRuntimeParameters parameters * **instance_id** : Body tracking instance id, by default the first instance ### function retrieveBodies ```cpp ERROR_CODE retrieveBodies( Bodies & bodies, unsigned int instance_id =0 ) ``` Retrieves body tracking data from the body tracking module. **Parameters**: * **bodies** : The tracked bodies 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. * **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. This method returns the result of the body tracking, 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. 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 body. ```cpp Bodies bodies; // Unique Bodies to be updated after each grab // --- Main loop while (true) { if (zed.grab() == ERROR_CODE::SUCCESS) { // Grab an image from the camera zed.retrieveBodies(bodies); for (auto body : bodies.body_list) { std::cout << body.label << std::endl; } } } ``` ### function retrieveBodies ```cpp ERROR_CODE retrieveBodies( Bodies & bodies, BodyTrackingRuntimeParameters parameters, unsigned int instance_id =0 ) ``` Retrieves body tracking data from the body tracking module. **Parameters**: * **bodies** : The tracked bodies 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. * **parameters** : Body tracking runtime settings, can be changed at each detection. In async mode, the parameters update is applied on the next iteration. * **instance_id** : Id of the body tracking instance. Used when multiple instances of the body tracking module are enabled at the same time. **Deprecated**: setBodyTrackingRuntimeParameters and retrieveBodies(Bodies &bodies, const unsigned int instance_id) functions should be used instead **Return**: ERROR_CODE::SUCCESS if everything went fine, ERROR_CODE::FAILURE otherwise. This method returns the result of the body tracking, 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. 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 body. ```cpp Bodies bodies; // Unique Bodies to be updated after each grab // --- Main loop while (true) { if (zed.grab() == ERROR_CODE::SUCCESS) { // Grab an image from the camera zed.retrieveBodies(bodies); for (auto body : bodies.body_list) { std::cout << body.label << std::endl; } } } ``` ### function isBodyTrackingEnabled ```cpp bool isBodyTrackingEnabled( unsigned int instance_id =0 ) ``` Tells if the body tracking module is enabled. ### function getBodyTrackingParameters ```cpp BodyTrackingParameters getBodyTrackingParameters( unsigned int instance_id =0 ) ``` Returns the BodyTrackingParameters used. **Return**: BodyTrackingParameters containing the parameters used for body tracking module initialization. It corresponds to the structure given as argument to the enableBodyTracking() method. ### function startPublishing ```cpp ERROR_CODE startPublishing( CommunicationParameters configuration =CommunicationParameters() ) ``` Set this camera as a data provider for the Fusion module. **Parameters**: * **configuration** : A structure containing all the initial parameters. Default: a preset of CommunicationParameters. **Return**: ERROR_CODE::SUCCESS if everything went fine, ERROR_CODE::FAILURE otherwise. **Note**: If you use it, you should include _sl/Fusion.hpp_ to avoid undefined reference. Metadata is exchanged with the Fusion. ### function stopPublishing ```cpp ERROR_CODE stopPublishing() ``` 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 ### function getCommunicationParameters ```cpp CommunicationParameters getCommunicationParameters() ``` 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. ### function Camera ```cpp Camera() ``` Default constructor. Creates an empty Camera object. The parameters will be set when calling open(init_param) with the desired InitParameters . A Camera object can be created like this: ```cpp Camera zed; ``` or ```cpp Camera* zed = new Camera(); ``` ### function ~Camera ```cpp ~Camera() ``` Class destructor. The destructor will call the close() function and clear the memory previously allocated by the object. ### function open ```cpp ERROR_CODE open( InitParameters init_parameters =InitParameters() ) ``` Opens the ZED camera from the provided InitParameters. **Parameters**: * **init_parameters** : 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. **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_ * If this method is called on an already opened camera, close() will be called. The method will also check the hardware requirements and run a self-calibration. Here is the proper way to call this function: ```cpp Camera zed; // Create a ZED camera object InitParameters init_params; // Set configuration parameters init_params.camera_resolution = RESOLUTION::HD720; // Use HD720 video mode init_params.camera_fps = 60; // Set fps at 60 // Open the camera ERROR_CODE err = zed.open(init_params); if (err != ERROR_CODE::SUCCESS) { std::cout << toString(err) << std::endl; // Display the error exit(-1); } ``` ### function getInitParameters ```cpp InitParameters getInitParameters() const ``` Returns the InitParameters used. **Return**: InitParameters containing the parameters used to initialize the Camera object. It corresponds to the structure given as argument to the open() method. ### function isOpened ```cpp inline bool isOpened() const ``` Reports if the camera has been successfully opened. **Return**: true if the ZED camera is already setup, otherwise false. It has the same behavior as checking if open() returns ERROR_CODE::SUCCESS. ### function close ```cpp void close() ``` Close an opened camera. **Note**: * If an asynchronous task is running within the Camera object, like saveAreaMap(), this method will wait for its completion. * 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. * Therefore you need to make sure to delete your GPU sl::Mat objects before the context is destroyed. 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 effects. ### function read ```cpp ERROR_CODE read() ``` Read the latest images and IMU from the camera and rectify the images. **Return**: ERROR_CODE::SUCCESS means that no problem was encountered. **Note**: * If no new frames is available until timeout is reached, read() will return ERROR_CODE::CAMERA_NOT_DETECTED since the camera has probably been disconnected. * Returned errors can be displayed using toString(). This method is meant to be called frequently in the main loop of your application. ### function grab ```cpp ERROR_CODE grab( RuntimeParameters rt_parameters =RuntimeParameters() ) ``` This method will call read if hasn't been called then compute the measurements based on the RuntimeParameters provided (depth, point cloud, tracking, etc.) **Parameters**: * **rt_parameters** : A structure containing all the runtime parameters. Default: a preset of RuntimeParameters. **Return**: ERROR_CODE::SUCCESS means that no problem was encountered. **Note**: * Since ZED SDK 3.0, this method is blocking. It means that grab() will wait until a new frame is detected and available. * 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. * Returned errors can be displayed using toString(). 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. * enablePositionalTracking() : 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. ```cpp // Set runtime parameters after opening the camera RuntimeParameters runtime_param; runtime_param.confidence_threshold = 50; // Change the confidence threshold Mat image; while (true) { // Grab an image if (zed.grab(runtime_param) == ERROR_CODE::SUCCESS) { // A new image is available if grab() returns SUCCESS zed.retrieveImage(image, VIEW::LEFT); // Get the left image // Use the image for your application } } ``` ### function getRuntimeParameters ```cpp RuntimeParameters getRuntimeParameters() const ``` Returns the RuntimeParameters used. **Return**: RuntimeParameters containing the parameters that define the behavior of the grab method. It corresponds to the structure given as argument to the grab() method. ### function getCameraInformation ```cpp CameraInformation getCameraInformation( Resolution image_size =Resolution(0, 0) ) const ``` Returns the CameraInformation associated the camera being used. **Parameters**: * **image_size** : 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 getCameraInformation().camera_configuration.resolution). **Return**: CameraInformation containing the calibration parameters of the ZED, as well as serial number and firmware version. **Note**: * The CameraInformation.camera_configuration will contain two types of calibration parameters: * camera_configuration.calibration_parameters: it contains the calibration for the **rectified** images. Rectified images are images that would come from perfect stereo camera (exact same camera, perfectly matched). Therefore, the camera matrix will be identical for left and right camera, and the distortion/rotation/translation matrix will be null (except for Tx, which is the exact distance between both eyes). * camera_configuration.calibration_parameters_raw: it contains the original calibration before rectification. Therefore it should be identical or very close to the calibration file SNXXXX.conf where XXXX is the serial number of the camera. * The calibration file SNXXXX.conf can be found in: * **Windows:**_C:/ProgramData/Stereolabs/settings/_ * **Linux:**_/usr/local/zed/settings/_ **Warning**: The returned parameters might vary between two execution due to the self-calibration being run in the open() method. 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. ### function updateSelfCalibration ```cpp void updateSelfCalibration() ``` Perform a new self-calibration process. **Note**: * The self calibration will occur at the next grab() call. * This method is similar to the previous resetSelfCalibration() used in 2.X SDK versions. **Warning**: New values will then be available in getCameraInformation(), be sure to get them to still have consistent 2D <-> 3D conversion. 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. ### function getCUDAContext ```cpp CUcontext getCUDAContext() ``` Gets the Camera-created CUDA context for sharing it with other CUDA-capable libraries. **Return**: The CUDA context used for GPU calls. **Note**: If you're looking for the opposite mechanism, where an existing CUDA context is given to the Camera, please check InitParameters::sdk_cuda_ctx This can be useful for sharing GPU memories. ### function getCUDAStream ```cpp CUstream getCUDAStream() ``` Gets the Camera-created CUDA stream for sharing it with other CUDA-capable libraries. **Return**: The CUDA stream used for GPU calls. ### function findPlaneAtHit ```cpp ERROR_CODE findPlaneAtHit( sl::uint2 coord, sl::Plane & plane, PlaneDetectionParameters parameters =PlaneDetectionParameters() ) ``` Checks the plane at the given left image coordinates. **Parameters**: * **coord** : The image coordinate. The coordinate must be taken from the full-size image. * **plane** : The detected plane if the method succeeded. * **parameters** : A structure containing all the specific parameters for the plane detection. Default: a preset of PlaneDetectionParameters. **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. This method gives the 3D plane corresponding to a given pixel in the latest left image 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. ### function findFloorPlane ```cpp ERROR_CODE findFloorPlane( sl::Plane & floorPlane, sl::Transform & resetTrackingFloorFrame, float floor_height_prior =INVALID_VALUE, sl::Rotation world_orientation_prior =sl::Matrix3f::zeros(), float floor_height_prior_tolerance =INVALID_VALUE ) ``` Detect the floor plane of the scene. **Parameters**: * **floorPlane** : The detected floor plane if the method succeeded. * **resetTrackingFloorFrame** : The transform to align the tracking with the floor plane. 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). * **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. If the prior is too far from the detected floor plane, the method will return ERROR_CODE::PLANE_NOT_FOUND. * **world_orientation_prior** : Prior set to locate the floor plane depending on the known camera orientation to the ground. If the prior is too far from the detected floor plane, the method will return ERROR_CODE::PLANE_NOT_FOUND. * **floor_height_prior_tolerance** : Prior height tolerance, absolute value. **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. * The length unit is defined by sl:InitParameters (coordinate_units). * 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. This method analysis 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. ### function getHealthStatus ```cpp HealthStatus getHealthStatus() ``` Returns HealthStatus. **Return**: HealthStatus Structure containing the self diagnostic results of the image/depth/sensors That self diagnostic can be enabled by sl::InitParameters::enable_image_validity_check ### function getRetrieveImageResolution ```cpp sl::Resolution getRetrieveImageResolution( sl::Resolution res =sl::Resolution(0, 0) ) ``` Get the resolution at which images are retrieved. **Parameters**: * **res** : Resolution used to retrieve the image. If set to (0,0), the resolution used to grab images is considered. **Return**: The resolution at which images are retrieved. ### function getRetrieveMeasureResolution ```cpp sl::Resolution getRetrieveMeasureResolution( sl::Resolution res =sl::Resolution(-1, -1) ) ``` Get the resolution at which depth and measure maps are retrieved. **Parameters**: * **res** : Resolution used to retrieve the measure. If set to (-1,-1), the resolution used to grab images is considered. **Return**: The resolution at which depth and measure maps are retrieved. ### function Camera ```cpp Camera( const Camera & ) =delete ``` The Camera object cannot be copied. Therfore, its copy constructor is disabled. **See**: Camera() If you need to share a Camera instance across several threads or object, please consider using a pointer. ### function getSDKVersion ```cpp static String getSDKVersion() ``` Returns the version of the currently installed ZED SDK. **Return**: The ZED SDK version as a string with the following format: MAJOR.MINOR.PATCH ```cpp std::cout << Camera::getSDKVersion() << std::endl; ``` ### function getSDKVersion ```cpp static void getSDKVersion( int & major, int & minor, int & patch ) ``` Returns the version of the currently installed ZED SDK. **Parameters**: * **major** : Major variable of the version filled. * **minor** : Minor variable of the version filled. * **patch** : Patch variable of the version filled. ```cpp int mj_v, mn_v,ptch_v; Camera::getSDKVersion(mj_v,mn_v,ptch_v); std::cout << "SDK Version v" << mj_v << "." << mn_v << "." << ptch_v << std::endl; ``` ### function getDeviceList ```cpp static std::vector< sl::DeviceProperties > getDeviceList() ``` List all the connected devices with their associated information. **Return**: The device properties for each connected camera. **Warning**: As this method returns an std::vector, it is only safe to use in Release or ReleaseWithDebugInfos mode (not Debug). This is due to a known compatibility issue between release (the SDK) and debug (your app) implementations of std::vector. This method lists all the cameras available and provides their serial number, models and other information. ### function setTimestampClock ```cpp static void setTimestampClock( TIMESTAMP_CLOCK clock ) ``` Sets the clock source used for all SDK timestamps (images and sensors). **Parameters**: * **clock** : The desired sl::TIMESTAMP_CLOCK. **Note**: Call this before opening any camera. This is a process-wide setting shared by all Camera and CameraOne instances. ### function getTimestampClock ```cpp static TIMESTAMP_CLOCK getTimestampClock() ``` Returns the clock source currently used for SDK timestamps. **Return**: The active sl::TIMESTAMP_CLOCK. ### function setMaxSystemClockStepMs ```cpp static void setMaxSystemClockStepMs( float limit_ms ) ``` 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. **Parameters**: * **limit_ms** : Clamp threshold. 4 ms by default; negative = disable; 0 = freeze. See sl::setMaxSystemClockStepMs() for the full cheat sheet and defaults. ### function getMaxSystemClockStepMs ```cpp static float getMaxSystemClockStepMs() ``` Returns the current system-clock step clamp in milliseconds. ### function getStreamingDeviceList ```cpp static std::vector< sl::StreamingProperties > getStreamingDeviceList() ``` List all the streaming devices with their associated information. **Return**: The streaming properties for each connected camera. **Warning**: * As this method returns an std::vector, it is only safe to use in Release or ReleaseWithDebugInfos mode (not Debug). This is due to a known compatibility issue between release (the SDK) and debug (your app) implementations of std::vector. * This method takes around 2 seconds to make sure all network informations has been captured. Make sure to run this method in a thread. ### function reboot ```cpp static sl::ERROR_CODE reboot( int sn, bool fullReboot =true ) ``` Performs a hardware reset of the ZED 2 and the ZED 2i. **Parameters**: * **sn** : Serial number of the camera to reset, or 0 to reset the first camera detected. * **fullReboot** : Perform a full reboot (sensors and video modules) if true, otherwise only the video module will be rebooted. **Return**: * ERROR_CODE::SUCCESS if everything went fine. * ERROR_CODE::CAMERA_NOT_DETECTED if no camera was detected. * 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. * Under Windows it is not possible to get exclusive access to HID devices, hence calling this method while the camera is opened by another process will cause it to freeze for a few seconds while the device is rebooting. ### function reboot ```cpp static sl::ERROR_CODE reboot( sl::INPUT_TYPE inputType ) ``` Performs a hardware reset of all devices matching the InputType. **Parameters**: * **inputType** : Input type of the devices to reset. **Return**: * ERROR_CODE::SUCCESS if everything went fine. * ERROR_CODE::CAMERA_NOT_DETECTED if no camera was detected. * ERROR_CODE::FAILURE for SVOs otherwise. * ERROR_CODE::INVALID_FUNCTION_PARAMETERS for SVOs and streams. **Warning**: * This method will invalidate any sl::Camera object, since the device is rebooting. * Under Windows it is not possible to get exclusive access to HID devices, hence calling this method while the camera is opened by another process will cause it to freeze for a few seconds while the device is rebooting. --- # sl::InitParameters **Module:** **Video Module** Class containing the options used to initialize the sl::Camera object. More... `#include ` ## Detailed Description ```cpp class sl::InitParameters; ``` Class containing the options used to initialize the sl::Camera object. **Note**: The parameters can also be saved and reloaded using its save() and load() methods. 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. ```cpp #include using namespace sl; int main(int argc, char **argv) { Camera zed; // Create a ZED camera object InitParameters init_params; // Set initial parameters init_params.sdk_verbose = 0; // Disable verbose mode // Use the camera in LIVE mode init_params.camera_resolution = 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.input.setFromSVOFile("xxxx.svo"); // Or use the camera in STREAM mode //init_params.input.setFromStream("192.168.1.12",30000); // Other parameters are left to their default values // Open the camera ERROR_CODE err = zed.open(init_params); if (err != ERROR_CODE::SUCCESS) exit(-1); // Close the camera zed.close(); return 0; } ``` 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 (or sl::DEPTH_MODE::NEURAL_LIGHT on Jetson). You can customize it to fit your application. ## Public Functions Documentation ### function InitParameters ```cpp InitParameters( RESOLUTION camera_resolution_ =RESOLUTION::AUTO, int camera_fps_ =0, bool svo_real_time_mode_ =false, DEPTH_MODE depth_mode_ =DEPTH_MODE::NEURAL, UNIT coordinate_units_ =UNIT::MILLIMETER, COORDINATE_SYSTEM coordinate_system_ =COORDINATE_SYSTEM::IMAGE, int sdk_verbose_ =1, int sdk_gpu_id_ =-1, float depth_minimum_distance_ =-1., float depth_maximum_distance_ =-1., bool camera_disable_self_calib_ =false, int camera_image_flip_ =FLIP_MODE::OFF, bool enable_right_side_measure_ =false, String sdk_verbose_log_file_ =String(), int depth_stabilization_ =30, CUcontext sdk_cuda_ctx_ =CUcontext(), InputType input_type =InputType(), String optional_settings_path_ =String(), bool sensors_required_ =false, bool enable_image_enhancement_ =true, String optional_opencv_calibration_file_ =String(), float open_timeout_sec_ =5.0f, bool async_grab_camera_recovery =false, float grab_compute_capping_fps =0, int enable_image_validity_check =true, bool async_image_retrieval =false, sl::Resolution maximum_working_resolution =sl::Resolution(0, 0), String svo_decryption_key =String() ) ``` Default constructor. All the parameters are set to their default and optimized values. ## Public Attributes Documentation ### variable camera_resolution ```cpp RESOLUTION camera_resolution; ``` Desired camera resolution. **Note**: * Small resolutions offer higher framerate and lower computation time. * In most situations, sl::RESOLUTION::HD720 at 60 FPS is the best balance between image quality and framerate. * Available resolutions are listed here: sl::RESOLUTION. Default: sl::RESOLUTION::AUTO * Resolves to sl::RESOLUTION::HD1200 for ZED X/X Mini * Resolves to sl::RESOLUTION::HD720 for other cameras ### variable camera_fps ```cpp int camera_fps; ``` Requested camera frame rate. **Note**: If the requested camera_fps is unsupported, the closest available FPS will be used. 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. ### variable camera_image_flip ```cpp int camera_image_flip; ``` Defines if a flip of the images is needed. **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. * This does not work on sl::MODEL::ZED cameras since they do not have the necessary sensors. 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::OFF ### variable camera_disable_self_calib ```cpp bool camera_disable_self_calib; ``` Disables the self-calibration process at camera opening. **Note**: * In most situations, self calibration should remain enabled. * You can also trigger the self-calibration at anytime after sl::Camera::open() by calling sl::Camera::updateSelfCalibration(), even if this parameter is set to true. 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 ### variable enable_right_side_measure ```cpp bool enable_right_side_measure; ``` 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 ### variable svo_real_time_mode ```cpp bool svo_real_time_mode; ``` Defines if sl::Camera object return the frame in real time mode. **Note**: sl::Camera::grab() will return an error when trying to play too fast, and frames will be dropped when playing too slowly. 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 ### variable depth_mode ```cpp DEPTH_MODE depth_mode; ``` 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_LIGHT for jetson devices else sl::DEPTH_MODE::NEURAL ### variable depth_stabilization ```cpp int depth_stabilization; ``` Defines whether the depth needs to be stabilized and to what extent. **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 that calling sl::Camera::enablePositionalTracking() with your own parameters afterwards is still possible. 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 ### variable depth_minimum_distance ```cpp float depth_minimum_distance; ``` 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). **Note**: This value cannot be greater than 3 meters. 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](https://www.stereolabs.com/docs/depth-sensing/depth-settings#depth-range). ### variable depth_maximum_distance ```cpp float depth_maximum_distance; ``` 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 sl::TOO_FAR 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 ### variable coordinate_units ```cpp UNIT coordinate_units; ``` Unit of spatial data (depth, point cloud, tracking, mesh, etc.) for retrieval. Default: sl::UNIT::MILLIMETER ### variable coordinate_system ```cpp COORDINATE_SYSTEM coordinate_system; ``` 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 ### variable sdk_gpu_id ```cpp CUdevice sdk_gpu_id; ``` NVIDIA graphics card to use. **Note**: A non-positive value will search for all CUDA capable devices and select the most powerful. 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 ### variable sdk_verbose ```cpp int sdk_verbose; ``` Enable the ZED SDK verbose mode. **Note**: * The verbose messages can also be exported into a log file. * See sdk_verbose_log_file for more. 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 message enabled) ### variable sdk_verbose_log_file ```cpp String sdk_verbose_log_file; ``` File path to store the ZED SDK logs (if sdk_verbose is enabled). **Note**: * Setting this parameter to any value will redirect all standard output print calls of the entire program. * This means that your own standard output print calls will be redirected to the log file. * This parameter can be particularly useful for creating a log system, and with Unreal or Unity applications that don't provide a standard console output. **Warning**: * The log file won't be cleared after successive executions of the application. * This means that it can grow indefinitely if not cleared. The file will be created if it does not exist. Default: "" ### variable sdk_cuda_ctx ```cpp CUcontext sdk_cuda_ctx; ``` CUcontext to be used. **Note**: * When creating you own CUDA context, you have to define the device you will use. Do not forget to also specify it on sdk_gpu_id. * **On Jetson**, you have to set the flag CU_CTX_SCHED_YIELD, during CUDA context creation. * You can also let the SDK create its own context, and use sl::Camera::getCUDAContext() to use it. * If you create your own CUDA context, you must ensure that it is destroyed after all SDK objects (sl::Camera, sl::Fusion) are destroyed. If your application uses another CUDA-capable library, giving its CUDA context to the ZED SDK can be useful when sharing GPU memories. This parameter allows you to set the CUDA context to be used by the ZED SDK. Leaving this parameter empty asks the SDK to create its own context. Default: (empty) ### variable input ```cpp InputType input; ``` Defines the input source to initialize and open an sl::Camera object from. **Note**: * Available cameras and their id/serial number can be listed using sl::Camera::getDeviceList() and sl::Camera::getStreamingDeviceList(). * Each sl::Camera will create its own memory (CPU and GPU), therefore the number of cameras used at the same time can be limited by the configuration of your computer (GPU/CPU memory and capabilities). * See sl::InputType for complementary information. 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) ```cpp InitParameters init_params; // Set initial parameters init_params.sdk_verbose = 1; // Enable verbose mode init_params.input.setFromCameraID(0); // Selects the camera with ID = 0 ``` * Select a camera by its serial number ```cpp InitParameters init_params; // Set initial parameters init_params.sdk_verbose = 1; // Enable verbose mode init_params.input.setFromSerialNumber(1010); // Selects the camera with serial number = 1010 ``` * Open a recorded sequence in the SVO file format ```cpp InitParameters init_params; // Set initial parameters init_params.sdk_verbose = 1; // Enable verbose mode init_params.input.setFromSVOFile("/path/to/file.svo"); // Selects the and SVO file to be read ``` * Open a streaming camera from its IP address and port ```cpp InitParameters init_params; // Set initial parameters init_params.sdk_verbose = 1; // Enable verbose mode init_params.input.setFromStream("192.168.1.42"); // Selects the IP address of the streaming camera. A second optional parameter is available for port selection. ``` Default : (empty) ### variable optional_settings_path ```cpp String optional_settings_path; ``` Optional path where the ZED SDK has to search for the settings file (_SN.conf_ file). **Note**: * The settings file will be searched in the default directory: * **Linux**: _/usr/local/zed/settings/_ * **Windows**: _C:/ProgramData/stereolabs/settings_ * If a path is specified and no file has been found, the ZED SDK will search the settings file in the default directory. * An automatic download of the settings file (through **ZED Explorer** or the installer) will still download the files on the default path. This file contains the calibration information of the camera. Default: "" ```cpp InitParameters init_params; // Set initial parameters std::string home = getenv("HOME"); // Get /home/user as string using getenv() std::string path = home + "/Documents/settings/"; // Assuming /home//Documents/settings/SNXXXX.conf exists. Otherwise, it will be searched in /usr/local/zed/settings/ init_params.optional_settings_path = sl::String(path.c_str()); ``` ### variable optional_opencv_calibration_file ```cpp String optional_opencv_calibration_file; ``` If set, the specific file will be loaded to overwrite the default factory calibration file. **Warning**: Erroneous calibration values can lead to poor accuracy in all ZED SDK modules. The file must be in a XML/YAML/JSON formatting provided by OpenCV. You can find a sample [here](https://www.stereolabs.com/docs/opencv/calibration#calibration-1) to generate your own calibration file and to have more information about the required format. ### variable sensors_required ```cpp bool sensors_required; ``` Requires the successful opening of the motion sensors before opening the camera. **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 parameter only impacts the LIVE mode. * If set to true, sl::Camera::open() will fail if the sensors cannot be opened. * This parameter should be used when the IMU data must be available, such as object detection module or when the gravity is needed. * This setting is not taken into account for sl::MODEL::ZED camera since it does not include sensors. Default: false. This can be used for example when using a USB3.0 only extension cable (some fiber extension for example). ### variable enable_image_enhancement ```cpp bool enable_image_enhancement; ``` Enable the Enhanced Contrast Technology, to improve image quality. **Note**: This only works for firmware version starting from 1523 and up. Default: true. If set to true, image enhancement will be activated in camera ISP. Otherwise, the image will not be enhanced by the IPS. ### variable open_timeout_sec ```cpp float open_timeout_sec; ``` Define a timeout in seconds after which an error is reported if the sl::Camera::open() method fails. **Note**: This parameter only impacts the LIVE mode. 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 ### variable async_grab_camera_recovery ```cpp bool async_grab_camera_recovery; ``` 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 ### variable grab_compute_capping_fps ```cpp float grab_compute_capping_fps; ``` Define a computation upper limit to the grab frequency. **Note**: * It has no effect when reading an SVO file. * Internally the sl::Camera::grab() method always tries to get the latest available image while respecting the desired FPS as much as possible. 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. This is an upper limit and won't make a difference if the computation is slower than the desired compute capping FPS. ### variable async_image_retrieval ```cpp bool async_image_retrieval; ``` If set to true will camera image retrieve at a framerate different from Camera::grab() application framerate. This is useful for recording SVO or sending camera stream at different rate than application. **Deprecated**: This parameter is deprecated and no longer has any effect. ### variable enable_image_validity_check ```cpp int enable_image_validity_check; ``` 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) ### variable maximum_working_resolution ```cpp sl::Resolution maximum_working_resolution; ``` Set a maximum size for all SDK output, like retrieveImage and retrieveMeasure functions. **Note**: : if maximum_working_resolution field are lower than 64, it will be interpreted as dividing scale factor; * maximum_working_resolution = sl::Resolution(1280, 2) -> 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 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 ### variable svo_decryption_key ```cpp String svo_decryption_key; ``` Optional passphrase or key to decrypt an encrypted SVO file. **Note**: If the SVO file is encrypted and this field is empty or contains a wrong key, sl::Camera::open() will return [ERROR_CODE::INVALID_SVO_FILE]. Required when opening an SVO file that was recorded with RecordingParameters::encryption_key. The value follows the same interpretation rules (file path, hex key, or passphrase). Default: "" (no decryption) --- # sl::RuntimeParameters **Module:** **Depth Sensing Module** Structure containing parameters that defines the behavior of sl::Camera::grab(). More... `#include ` ## Detailed Description ```cpp struct sl::RuntimeParameters; ``` Structure containing parameters that defines the behavior of sl::Camera::grab(). **Note**: Parameters can be adjusted by the user. The default constructor sets all parameters to their default settings. ## Public Functions Documentation ### function RuntimeParameters ```cpp RuntimeParameters( bool enable_depth_ =true, bool enable_fill_mode_ =false, int confidence_threshold_ =95, int texture_confidence_threshold_ =100, REFERENCE_FRAME measure3D_reference_frame_ =REFERENCE_FRAME::CAMERA, bool remove_saturated_areas_ =false ) ``` Default constructor. All the parameters are set to their default values. ## Public Attributes Documentation ### variable measure3D_reference_frame ```cpp REFERENCE_FRAME measure3D_reference_frame; ``` Reference frame in which to provides the 3D measures (point cloud, normals, etc.). Default: sl::REFERENCE_FRAME::CAMERA ### variable enable_depth ```cpp bool enable_depth; ``` Defines if the depth map should be computed. **Note**: If set to false, only the images are available. Default: true ### variable enable_fill_mode ```cpp bool enable_fill_mode = false; ``` Defines if the depth map should be completed or not. **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. Default: false ### variable confidence_threshold ```cpp int confidence_threshold = 95; ``` Threshold to reject depth values based on their confidence. **Note**: * Pixels with a value close to 100 are not to be trusted. Accurate depth pixels tends to be closer to lower values. * It can be seen as a probability of error, scaled to 100. 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 ### variable texture_confidence_threshold ```cpp int texture_confidence_threshold = 100; ``` Threshold to reject depth values based on their texture confidence. **Note**: Pixels with a value close to 100 are not to be trusted. Accurate depth pixels tends to be closer to lower values. 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) ### variable remove_saturated_areas ```cpp bool remove_saturated_areas = false; ``` Defines if the saturated area (luminance>=255) must be removed from depth map estimation. Default: false --- # sl::Mat **Module:** **Core Module** Class representing 1 to 4-channel matrix of float or uchar, stored on CPU and/or GPU side. More... `#include ` Inherited by Tensor ## Detailed Description ```cpp class sl::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. The CPU and GPU buffer aren't automatically synchronized for performance reasons, you can use updateCPUfromGPU / updateGPUfromCPU to do it. If you are using the GPU side of the sl::Mat object, you need to make sure to call free before destroying the sl::Camera object. The destruction of the sl::Camera object deletes the CUDA context needed to free the GPU sl::Mat memory. ## Public Functions Documentation ### function Mat ```cpp Mat() ``` Default constructor. The sl::Mat is empty (width = height = 0). ### function Mat ```cpp Mat( size_t width, size_t height, MAT_TYPE mat_type, MEM memory_type =MEM::CPU ) ``` Constructor. **Parameters**: * **width** : Width of the matrix in pixels. * **height** : Height of the matrix in pixels. * **mat_type** : Type of the matrix (sl::MAT_TYPE::F32_C1, sl::MAT_TYPE::U8_C4, etc.). * **memory_type** : Where the buffer will be stored (sl::MEM::CPU and/or sl::MEM::GPU). Initializes the sl::Mat and allocates the requested memory by calling alloc(). ### function Mat ```cpp Mat( size_t width, size_t height, MAT_TYPE mat_type, sl::uchar1 * ptr, size_t step, MEM memory_type =MEM::CPU ) ``` Constructor from an existing data pointer. **Parameters**: * **width** : Width of the matrix in pixels. * **height** : Height of the matrix in pixels. * **mat_type** : Type of the matrix (sl::MAT_TYPE::F32_C1, sl::MAT_TYPE::U8_C4, etc.). * **ptr** : Pointer to the data array (CPU or GPU). * **step** : Step of the data array (bytes size of one pixel row). * **memory_type** : Where the buffer will be stored (sl::MEM::CPU and/or sl::MEM::GPU). Initializes the sl::Mat but does not allocate the memory. ### function Mat ```cpp Mat( size_t width, size_t height, MAT_TYPE mat_type, sl::uchar1 * ptr_cpu, size_t step_cpu, sl::uchar1 * ptr_gpu, size_t step_gpu ) ``` Constructor from two existing data pointers, CPU and GPU. **Parameters**: * **width** : Width of the matrix in pixels. * **height** : Height of the matrix in pixels. * **mat_type** : Type of the matrix (sl::MAT_TYPE::F32_C1, sl::MAT_TYPE::U8_C4, etc.). * **ptr_cpu** : CPU pointer to the data array. * **step_cpu** : Step of the CPU data array (bytes size of one pixel row). * **ptr_gpu** : GPU pointer to the data array. * **step_gpu** : Step of the GPU data array (bytes size of one pixel row). Initializes the sl::Mat but does not allocate the memory. ### function Mat ```cpp Mat( Resolution resolution, MAT_TYPE mat_type, MEM memory_type =MEM::CPU ) ``` Constructor from an sl::Resolution. **Parameters**: * **resolution** : Size of the matrix in pixels. * **mat_type** : Type of the matrix (sl::MAT_TYPE::F32_C1, sl::MAT_TYPE::U8_C4, etc.). * **memory_type** : Where the buffer will be stored (sl::MEM::CPU and/or sl::MEM::GPU). Initializes the sl::Mat and allocates the requested memory by calling alloc(). ### function Mat ```cpp Mat( Resolution resolution, MAT_TYPE mat_type, sl::uchar1 * ptr, size_t step, MEM memory_type =MEM::CPU ) ``` Constructor from an existing data pointer. **Parameters**: * **resolution** : Size of the matrix in pixels. * **mat_type** : Type of the matrix (sl::MAT_TYPE::F32_C1, sl::MAT_TYPE::U8_C4, etc.). * **ptr** : Pointer to the data array (CPU or GPU). * **step** : Step of the data array (bytes size of one pixel row). * **memory_type** : Where the buffer will be stored (sl::MEM::CPU and/or sl::MEM::GPU). Initializes the sl::Mat but does not allocate the memory. ### function Mat ```cpp Mat( Resolution resolution, MAT_TYPE mat_type, sl::uchar1 * ptr_cpu, size_t step_cpu, sl::uchar1 * ptr_gpu, size_t step_gpu ) ``` Constructor from two existing data pointers, CPU and GPU. **Parameters**: * **resolution** : Size of the matrix in pixels. * **mat_type** : Type of the matrix (sl::MAT_TYPE::F32_C1, sl::MAT_TYPE::U8_C4, etc.). * **ptr_cpu** : CPU pointer to the data array. * **step_cpu** : Step of the CPU data array (bytes size of one pixel row). * **ptr_gpu** : GPU pointer to the data array. * **step_gpu** : Step of the GPU data array (bytes size of one pixel row). Initializes the sl::Mat but does not allocate the memory. ### function Mat ```cpp Mat( const Mat & mat ) ``` Copy constructor (shallow copy). **Parameters**: * **mat** : Reference to the sl::Mat to copy. Initializes the sl::Mat but does not allocate the memory. ### function alloc ```cpp void alloc( size_t width, size_t height, MAT_TYPE mat_type, MEM memory_type =MEM::CPU ) ``` Allocates the sl::Mat memory. **Parameters**: * **width** : Width of the matrix in pixels. * **height** : Height of the matrix in pixels. * **mat_type** : Type of the matrix (sl::MAT_TYPE::F32_C1, sl::MAT_TYPE::U8_C4, etc.). * **memory_type** : Where the buffer will be stored (sl::MEM::CPU and/or sl::MEM::GPU). **Warning**: It erases previously allocated memory. ### function alloc ```cpp void alloc( Resolution resolution, MAT_TYPE mat_type, MEM memory_type =MEM::CPU ) ``` Allocates the sl::Mat memory. **Parameters**: * **resolution** : Size of the matrix in pixels. * **mat_type** : Type of the matrix (sl::MAT_TYPE::F32_C1, sl::MAT_TYPE::U8_C4, etc.). * **memory_type** : Where the buffer will be stored (sl::MEM::CPU and/or sl::MEM::GPU). **Warning**: It erases previously allocated memory. ### function ~Mat ```cpp virtual ~Mat() ``` Destructor. This method calls free to release owned memory. ### function free ```cpp void free( MEM memory_type =MEM::BOTH ) ``` Free the owned memory. **Parameters**: * **memory_type** : Specifies whether you want to free the sl::MEM::CPU and/or sl::MEM::GPU memory. ### function operator= ```cpp Mat & operator=( const Mat & that ) ``` Performs a shallow copy. **Parameters**: * **that** : sl::Mat to be copied. **Return**: The new sl::Mat object which point to the same data as that. This method does not copy the data array, it only copies the pointer. ### function updateCPUfromGPU ```cpp ERROR_CODE updateCPUfromGPU( cudaStream_t stream =0 ) ``` Downloads data from DEVICE (GPU) to HOST (CPU), if possible. **Parameters**: * **stream** : Specifies the GPU stream to be used to enable asynchronous overlapping. Default: 0 (synchronous) **Return**: sl::ERROR_CODE::SUCCESS if everything went well, sl::ERROR_CODE::FAILURE otherwise. **Note**: * If no CPU or GPU memory are available for this sl::Mat, some are directly allocated. * If verbose is set to true, you have information in case of failure. ### function updateGPUfromCPU ```cpp ERROR_CODE updateGPUfromCPU( cudaStream_t stream =0, int GPU_id =0 ) ``` Uploads data from HOST (CPU) to DEVICE (GPU), if possible. **Parameters**: * **stream** : Specifies the GPU stream to be used to enable asynchronous overlapping. Default: 0 (synchronous) * **GPU_id** : Specifies the GPU id to be used. Default: 0 (first GPU). **Return**: sl::ERROR_CODE::SUCCESS if everything went well, sl::ERROR_CODE::FAILURE otherwise. **Note**: * If no CPU or GPU memory are available for this sl::Mat, some are directly allocated. * If verbose is set to true, you have information in case of failure. ### function copyTo ```cpp ERROR_CODE copyTo( Mat & dst, COPY_TYPE cpyType =COPY_TYPE::CPU_CPU, cudaStream_t stream =0 ) const ``` Copies data an other sl::Mat (deep copy). **Parameters**: * **dst** : sl::Mat where the data will be copied. * **cpyType** : Specifies the memory that will be used for the copy. * **stream** : Specifies the GPU stream to be used to enable asynchronous overlapping. Default: 0 (synchronous) **Return**: sl::ERROR_CODE::SUCCESS if everything went well, sl::ERROR_CODE::FAILURE otherwise. **Note**: If the destination is not allocated or or doesn't have a compatible sl::MAT_TYPE or sl::Resolution, current memory is freed and new memory is directly allocated. ### function setFrom ```cpp ERROR_CODE setFrom( const Mat & src, COPY_TYPE cpyType =COPY_TYPE::CPU_CPU, cudaStream_t stream =0 ) ``` Copies data from an other sl::Mat (deep copy). **Parameters**: * **src** : sl::Mat where the data will be copied from. * **cpyType** : Specifies the memory that will be used for the copy. * **stream** : Specifies the GPU stream to be used to enable asynchronous overlapping. Default: 0 (synchronous) **Return**: sl::ERROR_CODE::SUCCESS if everything went well, sl::ERROR_CODE::FAILURE otherwise. **Note**: If the destination is not allocated or or doesn't have a compatible sl::MAT_TYPE or sl::Resolution, current memory is freed and new memory is directly allocated. ### function read ```cpp ERROR_CODE read( const String & filePath ) ``` Reads an image from a file. **Parameters**: * **filePath** : Path of the file to read (including the name and extension). **Return**: sl::ERROR_CODE::SUCCESS if everything went well, sl::ERROR_CODE::FAILURE otherwise. **Note**: This method only support images such as JPG or PNG, and can't load float format such as PCD, PLY, etc. ### function write ```cpp ERROR_CODE write( const String & filePath, sl::MEM memory_type =sl::MEM::CPU, int compression_level =-1 ) ``` Writes the sl::Mat (only if sl::MEM::CPU is available) into a file defined by its extension. **Parameters**: * **filePath** : Path of the file to write in (including the name and extension). * **memory_type** : Memory type (CPU or GPU) of the sl::Mat. * **compression_level** : Level of compression between 0 (lowest compression == highest size == highest quality(jpg)) and 100 (highest compression == lowest size == lowest quality(jpg)). **Return**: sl::ERROR_CODE::SUCCESS if everything went well, sl::ERROR_CODE::FAILURE otherwise. **Note**: * Specific/default value for compression_level = -1 : This will set the default quality for PNG(30) or JPEG(5). * **compression_level** is only supported for U8_Cx sl::MAT_TYPE. * Supported sl::MAT_TYPE are: * sl::MAT_TYPE::F32_C1 for PNG/PFM/PGM * sl::MAT_TYPE::F32_C3 for PCD/PLY/VTK/XYZ * sl::MAT_TYPE::F32_C4 for PCD/PLY/VTK/WYZ * sl::MAT_TYPE::U8_C1 for PNG/JPG * sl::MAT_TYPE::U8_C3 for PNG/JPG * sl::MAT_TYPE::U8_C4 for PNG/JPG ### function setTo ```cpp template ERROR_CODE setTo( const T & value, const sl::MEM memory_type =MEM::CPU, cudaStream_t stream =0 ) ``` Fills the sl::Mat with the given value. **Parameters**: * **value** : Value to be copied all over the matrix. * **memory_type** : Which buffer to fill, CPU and/or GPU. * **stream** : a cuda stream to put the compute to (default 0). **Return**: sl::ERROR_CODE::SUCCESS if everything went well, sl::ERROR_CODE::FAILURE otherwise. **Note**: This method is templated for sl::uchar1, sl::uchar2, sl::uchar3, sl::uchar4, sl::float1, sl::float2, sl::float3, sl::float4, sl::char4, sl::ushort1. This method overwrites all the matrix. ### function setValue ```cpp template ERROR_CODE setValue( const size_t x, const size_t y, const N & value, const sl::MEM memory_type =MEM::CPU ) ``` Sets a value to a specific point in the matrix. **Parameters**: * **x** : Column of the point to change. * **y** : Row of the point to change. * **value** : Value to be set. * **memory_type** : Which memory will be updated. **Return**: sl::ERROR_CODE::SUCCESS if everything went well, sl::ERROR_CODE::FAILURE otherwise. **Note**: This method is templated for sl::uchar1, sl::uchar2, sl::uchar3, sl::uchar4, sl::float1, sl::float2, sl::float3, sl::float4, sl::char4, sl::ushort1. **Warning**: Not efficient for sl::MEM::GPU, use it on sparse data. ### function getValue ```cpp template ERROR_CODE getValue( const size_t x, const size_t y, N * value, const MEM memory_type =MEM::CPU ) const ``` Get the value of a specific point in the matrix. **Parameters**: * **x** : Column of the point to get the value from. * **y** : Row of the point to get the value from. * **value** : Pointer to the value to be filled. * **memory_type** : Which memory should be read. **Return**: sl::ERROR_CODE::SUCCESS if everything went well, sl::ERROR_CODE::FAILURE otherwise. **Note**: This method is templated for sl::uchar1, sl::uchar2, sl::uchar3, sl::uchar4, sl::float1, sl::float2, sl::float3, sl::float4, sl::char4, sl::ushort1. **Warning**: Not efficient for sl::MEM::GPU, use it on sparse data. ### function getWidth ```cpp inline size_t getWidth() const ``` Returns the width of the matrix. **Return**: Width of the matrix in pixels. ### function getHeight ```cpp inline size_t getHeight() const ``` Returns the height of the matrix. **Return**: Height of the matrix in pixels. ### function getResolution ```cpp inline const Resolution & getResolution() const ``` Returns the resolution (width and height) of the matrix. **Return**: Resolution of the matrix in pixels. ### function getResolution ```cpp inline Resolution getResolution() ``` Returns the resolution (width and height) of the matrix. **Return**: Resolution of the matrix in pixels. ### function getResolution ```cpp void getResolution() const =delete ``` Prevent method from being called by temporaries (such as rvalue) ### function getChannels ```cpp inline size_t getChannels() const ``` Returns the number of values stored in one pixel. **Return**: Number of values in a pixel. ### function getDataType ```cpp inline MAT_TYPE getDataType() const ``` Returns the format of the matrix. **Return**: Format of the current sl::Mat. ### function getMemoryType ```cpp inline MEM getMemoryType() const ``` Returns the type of memory (CPU and/or GPU). **Return**: Type of allocated memory. ### function getPtr ```cpp template N * getPtr( const MEM memory_type =MEM::CPU ) const ``` Returns the CPU or GPU data pointer. **Parameters**: * **memory_type** : Specifies whether you want sl::MEM::CPU or sl::MEM::GPU. **Return**: The pointer of the Mat data. ### function getStepBytes ```cpp size_t getStepBytes( const MEM memory_type =MEM::CPU ) const ``` Returns the memory step in bytes (size of one pixel row). **Parameters**: * **memory_type** : Specifies whether you want sl::MEM::CPU or sl::MEM::GPU step. **Return**: The step in bytes of the specified memory. ### function getStep ```cpp template inline size_t getStep( const MEM memory_type =MEM::CPU ) const ``` Returns the memory step in number of elements (size in one pixel row). **Parameters**: * **memory_type** : Specifies whether you want sl::MEM::CPU or sl::MEM::GPU step. **Return**: The step in number of elements. ### function getStep ```cpp inline size_t getStep( MEM memory_type =MEM::CPU ) const ``` Returns the memory step in number of elements (size in one pixel row). **Parameters**: * **memory_type** : Specifies whether you want sl::MEM::CPU or sl::MEM::GPU step. **Return**: The step in number of elements. ### function getPixelBytes ```cpp inline size_t getPixelBytes() const ``` Returns the size of one pixel in bytes. **Return**: Size of a pixel in bytes. ### function getWidthBytes ```cpp inline size_t getWidthBytes() const ``` Returns the size of a row in bytes. **Return**: Size of a row in bytes. ### function getInfos ```cpp String getInfos() const ``` Returns the information about the sl::Mat into a sl::String. **Return**: String containing the sl::Mat information. ### function isInit ```cpp inline bool isInit() const ``` Returns whether the sl::Mat is initialized or not. **Return**: True if current sl::Mat has been allocated (by the constructor or therefore). ### function isMemoryOwner ```cpp inline bool isMemoryOwner() const ``` Returns whether the sl::Mat is the owner of the memory it accesses. **Return**: True if the sl::Mat is owning its memory, else false. If not, the memory won't be freed if the sl::Mat is destroyed. ### function clone ```cpp ERROR_CODE clone( const Mat & src ) ``` Duplicates a sl::Mat by copy (deep copy). **Parameters**: * **src** : Reference of the sl::Mat to copy. This method copies the data array(s) and it marks the new sl::Mat as the memory owner. ### function move ```cpp ERROR_CODE move( Mat & dst ) ``` Moves the data of the sl::Mat to another sl::Mat. **Parameters**: * **dst** : Reference to the sl::Mat to move to. **Note**: : The current sl::Mat is then no more usable since its loose its attributes. This method gives the attribute of the current s::Mat to the specified one. (No copy.) ### function convertColor ```cpp ERROR_CODE convertColor( sl::MEM memory =sl::MEM::CPU, cudaStream_t stream =0, bool swap_RB_channels =true ) ``` Convert the color channels of the Mat (RGB<->BGR or RGBA<->BGRA) This methods works only on 8U_C4 or 8U_C3. ### function swap ```cpp static void swap( Mat & mat1, Mat & mat2 ) ``` Swaps the content of the provided sl::Mat (only swaps the pointers, no data copy). **Parameters**: * **mat1** : First matrix to swap. * **mat2** : Second matrix to swap. This method swaps the pointers of the given sl::Mat. ### function convertColor ```cpp static ERROR_CODE convertColor( Mat & mat1, Mat & mat2, bool swap_RB_channels, bool remove_alpha_channels, sl::MEM memory =sl::MEM::CPU, cudaStream_t stream =0 ) ``` 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. ## Protected Functions Documentation ### function ref ```cpp void ref( const Mat & mat ) ``` ## Public Attributes Documentation ### variable name ```cpp String name; ``` Variable used in verbose mode to indicate which sl::Mat is printing informations. Default set to "n/a" to avoid empty string if not filled. ### variable verbose ```cpp bool verbose = false; ``` Whether the sl::Mat can display informations. ### variable timestamp ```cpp Timestamp timestamp = 0; ``` Timestamp of the last manipulation of the data of the matrix by a method/function. ## Protected Attributes Documentation ### variable size ```cpp Resolution size; ``` ### variable channels ```cpp size_t channels = 0; ``` ### variable step_gpu ```cpp size_t step_gpu = 0; ``` ### variable step_cpu ```cpp size_t step_cpu = 0; ``` ### variable pixel_bytes ```cpp size_t pixel_bytes = 0; ``` ### variable data_type ```cpp MAT_TYPE data_type = MAT_TYPE::U8_C1; ``` ### variable mem_type ```cpp MEM mem_type = MEM::CPU; ``` ### variable ptr_cpu ```cpp std::shared_ptr< uchar1 > ptr_cpu = NULL; ``` ### variable ptr_gpu ```cpp std::shared_ptr< uchar1 > ptr_gpu = NULL; ``` ### variable init ```cpp bool init = false; ``` ### variable memory_owner ```cpp bool memory_owner = false; ``` --- # sl @HideINTERNAL_PUBLICAPI_START More... ## Classes | | Name | | -------------- | -------------- | | struct | **sl::RecordingStatus**
Structure containing information about the status of the recording. | | class | **sl::InitParameters**
Class containing the options used to initialize the sl::Camera object. | | struct | **sl::RuntimeParameters**
Structure containing parameters that defines the behavior of sl::Camera::grab(). | | class | **sl::PositionalTrackingParameters**
Structure containing a set of parameters for the positional tracking module initialization. | | struct | **sl::VoxelMeasureParameters**
Parameters controlling voxel decimation in sl::Camera::retrieveVoxelMeasure. | | class | **sl::SpatialMappingParameters**
Structure containing a set of parameters for the spatial mapping module. | | struct | **sl::StreamingParameters**
Structure containing the options used to stream with the ZED SDK. | | struct | **sl::RecordingParameters**
Structure containing the options used to record. | | struct | **sl::RawBuffer**
Zero-copy wrapper for native camera capture buffers. | | class | **sl::Camera**
This class serves as the primary interface between the camera and the various features provided by the SDK. | | class | **sl::InitParametersOne**
Class containing the options used to initialize the sl::CameraOne object. | | struct | **sl::CameraOneConfiguration**
Structure containing information about the camera sensor. | | struct | **sl::CameraOneInformation**
Structure containing information of a single camera (serial number, model, input type, etc.). | | class | **sl::CameraOne**
This class serves as the primary interface between the camera and the various features provided by the SDK when using Monocular cameras. | | struct | **sl::LidarCalibration**
Structure containing beam geometry calibration data for raw data processing. | | struct | **sl::LidarSensorConfiguration**
Structure containing runtime configuration of the Lidar sensor. | | struct | **sl::LidarInformation**
Structure containing information about the Lidar device. | | struct | **sl::LidarDeviceProperties**
Structure containing properties of a discovered Lidar device. | | class | **sl::InitLidarParameters**
Structure containing the options used to initialize the Lidar object. | | class | **sl::PositionalTrackingLidarParameters**
Structure containing the options used to enable positional tracking with Lidar. | | class | **sl::RecordingLidarParameters**
Structure containing the options used to record Lidar data. | | class | **sl::Lidar**
Class for Lidar control and data retrieval. It provides methods to initialize the Lidar, retrieve data, and enable positional tracking. Supports both live sensor input and OSF file playback. | | class | **sl::SensorDeviceIdentifier**
Structure containing information about a sensor device (camera or lidar) managed by the Sensors class. | | struct | **sl::InitSensorsParameters** | | struct | **sl::ObjectDetectionSensorsParameters** | | struct | **sl::BodyTrackingSensorsParameters** | | struct | **sl::BodyTrackingSensorsRuntimeParameters**
Structure containing a set of runtime parameters for the body tracking module. | | struct | **sl::PositionalTrackingSensorsParameters** | | struct | **sl::RecordingSensorsParameters** | | struct | **sl::StreamingSensorsParameters** | | struct | **sl::RuntimeSensorsParameters** | | struct | **sl::SensorList**
Structure containing lists of all available sensor devices. | | struct | **sl::StreamingSensorList**
Structure containing lists of all available streaming sensor devices. | | class | **sl::Sensors**
Class for managing multiple sensors (Cameras, Lidars) and fusing their data. | | class | **sl::String**
Class defining a string. | | struct | **sl::Resolution**
Structure containing the width and height of an image. | | class | **sl::Rect**
Class defining a 2D rectangle with top-left corner coordinates and width/height in pixels. | | struct | **sl::DeviceProperties**
Structure containing information about the properties of a camera. | | struct | **sl::CameraParameters**
Structure containing the intrinsic parameters of a camera. | | struct | **sl::StreamingProperties**
Structure containing information about the properties of a streaming device. | | class | **sl::InputType**
Class defining the input type used in the ZED SDK. | | class | **sl::AI_Model_status**
Structure containing AI model status. | | class | **sl::Matrix3f**
Class representing a generic 3*3 matrix. | | class | **sl::Matrix4f**
Class representing a generic 4*4 matrix. | | class | **sl::Vector2**
Class representing a 2-dimensional vector for both CPU and GPU. | | class | **sl::Vector3**
Class representing a 3-dimensional vector for both CPU and GPU. | | class | **sl::Vector4**
Class representing a 4-dimensional vector for both CPU and GPU. | | struct | **sl::Timestamp**
Structure representing timestamps with utilities. | | class | **sl::Mat**
Class representing 1 to 4-channel matrix of float or uchar, stored on CPU and/or GPU side. | | struct | **sl::TensorParameters**
Structure to define the input options for deep learning inference. | | class | **sl::Tensor**
Class representing a multi-dimensional array (Tensor), typically used for deep learning inference. | | class | **sl::Rotation**
Class representing a rotation for the positional tracking module. | | class | **sl::Translation**
Class representing a translation for the positional tracking module. | | class | **sl::Orientation**
Class representing an orientation/quaternion for the positional tracking module. | | class | **sl::Transform**
Class representing a transformation (translation and rotation) for the positional tracking module. | | struct | **sl::CalibrationParameters**
Structure containing intrinsic and extrinsic parameters of the camera (translation and rotation). | | struct | **sl::SensorParameters**
Structure containing information about a single sensor available in the current device. | | struct | **sl::SensorsConfiguration**
Structure containing information about all the sensors available in the current device. | | struct | **sl::CameraConfiguration**
Structure containing information about the camera sensor. | | struct | **sl::CameraInformation**
Structure containing information of a single camera (serial number, model, input type, etc.). | | class | **sl::Pose**
Class containing positional tracking data giving the position and orientation of the camera in 3D space. | | class | **sl::Landmark**
Represents a 3d landmark. | | class | **sl::Landmark2D**
Represents the projection of a 3d landmark in the image. | | class | **sl::KeyFrame**
Represents a keyframe in the tracking system. | | struct | **sl::SensorsData**
Structure containing all sensors data (except image sensors) to be used for positional tracking or environment study. | | class | **sl::ObjectData**
Class containing data of a detected object such as its bounding_box, label, id and its 3D position. | | class | **sl::CustomBoxObjectData**
Class that store externally detected objects. | | class | **sl::CustomMaskObjectData**
Class that store externally detected objects with mask. | | class | **sl::Objects**
Class containing the results of the object detection module. | | class | **sl::BodyData**
Class containing data of a detected body/person such as its bounding_box, id and its 3D position. | | class | **sl::Bodies**
Class containing the results of the body tracking module. | | class | **sl::ObjectsBatch**
Class containing batched data of a detected objects from the object detection module. | | class | **sl::BodiesBatch**
Class containing batched data of a detected bodies/persons from the body tracking module. | | class | **sl::CommunicationParameters**
Holds the communication parameter to configure the connection between senders and receiver. | | struct | **sl::SVOData** | | struct | **sl::HealthStatus** | | class | **sl::PositionalTrackingStatus**
Lists the different status of positional tracking. | | class | **sl::BatchParameters**
Structure containing a set of parameters for batch object detection. | | class | **sl::ObjectDetectionParameters**
Structure containing a set of parameters for the object detection module. | | class | **sl::ObjectTrackingParameters**
Structure containing a set of parameters for the object tracking module. | | class | **sl::ObjectDetectionRuntimeParameters**
Structure containing a set of runtime parameters for the object detection module. | | class | **sl::CustomObjectDetectionProperties**
Structure containing a set of runtime properties of a certain class ID for the object detection module using a custom model. | | class | **sl::CustomObjectDetectionRuntimeParameters**
Structure containing a set of runtime parameters for the object detection module using your own model ran by the SDK. | | struct | **sl::BodyTrackingParameters**
Structure containing a set of parameters for the body tracking module. | | struct | **sl::BodyTrackingRuntimeParameters**
Structure containing a set of runtime parameters for the body tracking module. | | class | **sl::PlaneDetectionParameters**
Structure containing a set of parameters for the plane detection functionality. | | struct | **sl::RegionOfInterestParameters** | | class | **sl::ECEF**
Represents a world position in ECEF format. | | class | **sl::LatLng**
Represents a world position in LatLng format. | | class | **sl::UTM**
Represents a world position in UTM format. | | class | **sl::ENU**
Represents a world position in ENU format. | | class | **sl::GeoConverter**
Purely static class for Geo functions. | | class | **sl::GeoPose**
Holds geographic reference position information. | | class | **sl::GNSSData**
Class containing GNSS data to be used for positional tracking as prior. | | class | **sl::FusedPositionalTrackingStatus**
Class containing the overall position fusion status. | | class | **sl::GNSSCalibrationParameters**
Holds the options used for calibrating GNSS / VIO. | | class | **sl::MeshFilterParameters**
Class containing a set of parameters for the mesh filtration functionality. | | class | **sl::Chunk**
Class representing a sub-mesh containing local vertices and triangles. | | class | **sl::Mesh**
Class representing a mesh and containing the geometric (and optionally texture) data of the scene captured by the spatial mapping module. | | class | **sl::Plane**
Class representing a plane defined by a point and a normal, or a plane equation. | | class | **sl::PointCloudChunk**
Class representing a sub-point cloud containing local vertices and colors. | | class | **sl::FusedPointCloud**
Class representing a fused point cloud and containing the geometric and color data of the scene captured by the spatial mapping module. | | class | **sl::CameraIdentifier**
Used to identify a specific camera in the Fusion API. | | class | **sl::FusionConfiguration**
Useful struct to store the Fusion configuration, can be read from /write to a JSON file. | | struct | **sl::SynchronizationParameter**
Configuration parameters for data synchronization. | | class | **sl::InitFusionParameters**
Holds the options used to initialize the Fusion object. | | class | **sl::BodyTrackingFusionParameters**
Holds the options used to initialize the body tracking module of the Fusion. | | class | **sl::BodyTrackingFusionRuntimeParameters**
Holds the options used to change the behavior of the body tracking module at runtime. | | class | **sl::ObjectDetectionFusionParameters**
Holds the options used to initialize the object detection module of the Fusion. | | class | **sl::PositionalTrackingFusionParameters**
Holds the options used for initializing the positional tracking fusion module. | | class | **sl::SpatialMappingFusionParameters**
Sets the spatial mapping parameters. | | class | **sl::CameraMetrics**
Holds the metrics of a sender in the fusion process. | | class | **sl::FusionMetrics**
Holds the metrics of the fusion process. | | class | **sl::Fusion**
Holds Fusion process data and functions. | ## Detailed Description @HideINTERNAL_PUBLICAPI_START @HideINTERNAL_PUBLICAPI_END ## Types Documentation ### typedef float1 ```cpp typedef float float1; ``` ### typedef float2 ```cpp typedef Vector2 float2; ``` ### typedef float3 ```cpp typedef Vector3 float3; ``` ### typedef float4 ```cpp typedef Vector4 float4; ``` ### typedef uchar1 ```cpp typedef unsigned char uchar1; ``` ### typedef uchar2 ```cpp typedef Vector2 uchar2; ``` ### typedef uchar3 ```cpp typedef Vector3 uchar3; ``` ### typedef uchar4 ```cpp typedef Vector4 uchar4; ``` ### typedef double1 ```cpp typedef double double1; ``` ### typedef double2 ```cpp typedef Vector2 double2; ``` ### typedef double3 ```cpp typedef Vector3 double3; ``` ### typedef double4 ```cpp typedef Vector4 double4; ``` ### typedef uint1 ```cpp typedef unsigned int uint1; ``` ### typedef uint2 ```cpp typedef Vector2 uint2; ``` ### typedef int2 ```cpp typedef Vector2 int2; ``` ### typedef int3 ```cpp typedef Vector3 int3; ``` ### typedef uint3 ```cpp typedef Vector3 uint3; ``` ### typedef uint4 ```cpp typedef Vector4 uint4; ``` ### typedef ushort1 ```cpp typedef unsigned short ushort1; ``` ### typedef char4 ```cpp typedef Vector4 char4; ``` ### enum SIDE | Enumerator | Value | Description | | ---------- | ----- | ----------- | | LEFT | | Left side only. | | RIGHT | | Right side only. | | BOTH | | Left and right side. | Lists possible sides on which to get data from. ### enum FLIP_MODE | Enumerator | Value | Description | | ---------- | ----- | ----------- | | OFF | 0| No flip applied. Default behavior. | | ON | 1| Images and camera sensors' data are flipped useful when your camera is mounted upside down. | | AUTO | 2| 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. | Lists possible flip modes of the camera. ### enum RESOLUTION | Enumerator | Value | Description | | ---------- | ----- | ----------- | | HD4K | | 3856x2180 for imx678 mono | | QHDPLUS | | 3800x1800 | | HD2K | | 2208*1242 (x2) Available FPS: 15 Only supported with ZED-M / ZED2i | | HD1536 | | 1920*1536 (x2) Available FPS: 30 Only supported with ZED-X HDR lineup (One/Stereo) | | HD1080 | | 1920*1080 (x2) Available FPS: 15, 30 | | HD1200 | | 1920*1200 (x2) Available FPS: 15, 30, 60 Only supported with ZED-X lineup (One/Stereo) and ZED-XOne 4K | | HD720 | | 1280*720 (x2) Available FPS: 15, 30, 60 | | SVGA | | 960*600 (x2) Available FPS: 15, 30, 60, 120 Only supported with ZED-X lineup (One/Stereo) | | 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 * ZED X Pro/X Pro Mini: HD1536 * other cameras: HD720 | 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. * You can find the available resolutions for each camera in [our documentation](https://www.stereolabs.com/docs/video/camera-controls#selecting-a-resolution). ### enum VIDEO_SETTINGS | Enumerator | Value | Description | | ---------- | ----- | ----------- | | BRIGHTNESS | | Brightness control Affected value should be between 0 and 8. | | CONTRAST | | Contrast control Affected value should be between 0 and 8. | | HUE | | Hue control Affected value should be between 0 and 11. | | 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. | | 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 overloaded setCameraSettings() / getCameraSettings() methods. | | WHITEBALANCE_TEMPERATURE | | Color temperature control Affected value should be between 2800 and 6500 with a step of 100. | | 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. | | EXPOSURE_TIME | | Exposure time of the sensor in microseconds. | | ANALOG_GAIN | | Analog gain (sensor) control in mDB. | | DIGITAL_GAIN | | Digital gain (ISP) as a factor. | | AUTO_EXPOSURE_TIME_RANGE | | Range of exposure auto control in microseconds. Used with setCameraSettings(). Min/max range between max range defined in DTS. By default: [28000 - or 19000] us. | | AUTO_ANALOG_GAIN_RANGE | | Range of sensor gain in automatic control. Used with setCameraSettings(). Min/max range between max range defined in DTS. By default: [1000 - 16000] mdB. | | AUTO_DIGITAL_GAIN_RANGE | | Range of digital ISP gain in automatic control. Used with setCameraSettings(). Min/max range between max range defined in DTS. By default: [1 - 256]. | | 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. | | DENOISING | | Level of denoising applied on both left and right images. Affected value should be between 0 and 100. Default value is 50. | | SCENE_ILLUMINANCE | | Level of illuminance of the scene calculated by the ISP. Can be used to determine the level of light in the scene and adjust settings accordingly. | | 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). | 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](https://www.stereolabs.com/docs/video/camera-controls#adjusting-camera-settings). GAIN and EXPOSURE are linked in auto/default mode (see sl::Camera::setCameraSettings()). ### enum DEPTH_MODE | Enumerator | Value | Description | | ---------- | ----- | ----------- | | NONE | | No depth map computation. Only rectified stereo images will be available. | | PERFORMANCE | | | | QUALITY | | | | ULTRA | | | | NEURAL_LIGHT | | End to End Neural disparity estimation. Requires AI module. | | NEURAL | | End to End Neural disparity estimation. Requires AI module. | | NEURAL_PLUS | | More accurate Neural disparity estimation. Requires AI module. | Lists available depth computation modes. ### enum MEASURE | Enumerator | Value | Description | | ---------- | ----- | ----------- | | 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 should 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 should 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 should 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 should 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. | Lists retrievable measures. ### enum VIEW | Enumerator | Value | Description | | ---------- | ----- | ----------- | | LEFT | | Left (for stereo or default for monocular camera) 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. Type: sl::MAT_TYPE::NV12 | | RIGHT_NV12_UNRECTIFIED | | Right NV12 unrectified image. 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 | | CONFIDENCE | | Color rendering of the depth confidence. Each pixel contains 4 unsigned char (B, G, R, A). Type: sl::MAT_TYPE::U8_C4 | | NORMALS | | Color rendering of the normals. Each pixel contains 4 unsigned char (B, G, R, A). Type: sl::MAT_TYPE::U8_C4 | | 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 | | 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 | | LEFT_BGRA | | Alias of sl::VIEW::LEFT. Type: sl::MAT_TYPE::U8_C4 | | LEFT_BGR | | Left image in BGR pixel format: Type: sl::MAT_TYPE::U8_C3 | | RIGHT_BGRA | | Alias of sl::VIEW::RIGHT. Type: sl::MAT_TYPE::U8_C4 | | RIGHT_BGR | | Right image in BGR pixel format: Type: sl::MAT_TYPE::U8_C3 | | LEFT_UNRECTIFIED_BGRA | | Alias of sl::VIEW::LEFT_UNRECTIFIED. Type: sl::MAT_TYPE::U8_C4 | | LEFT_UNRECTIFIED_BGR | | Left unrectified image in BGR pixel format: Type: sl::MAT_TYPE::U8_C3 | | RIGHT_UNRECTIFIED_BGRA | | Alias of sl::VIEW::RIGHT_UNRECTIFIED. Type: sl::MAT_TYPE::U8_C4 | | RIGHT_UNRECTIFIED_BGR | | Right unrectified image in BGR pixel format: Type: sl::MAT_TYPE::U8_C3 | | SIDE_BY_SIDE_BGRA | | Alias of sl::VIEW::SIDE_BY_SIDE. Type: sl::MAT_TYPE::U8_C4 | | SIDE_BY_SIDE_BGR | | Side by side image in BGR pixel format: Type: sl::MAT_TYPE::U8_C3 | | SIDE_BY_SIDE_GRAY | | Side by side image in gray scale: Type: sl::MAT_TYPE::U8_C1 | | SIDE_BY_SIDE_UNRECTIFIED_BGRA | | Alias of sl::VIEW::SIDE_BY_SIDE_UNRECTIFIED. Type: sl::MAT_TYPE::U8_C4 | | SIDE_BY_SIDE_UNRECTIFIED_BGR | | Side by side unrectified image in BGR pixel format: Type: sl::MAT_TYPE::U8_C3 | | SIDE_BY_SIDE_UNRECTIFIED_GRAY | | Side by side unrectified image in gray scale: Type: sl::MAT_TYPE::U8_C1 | | DEPTH_BGRA | | Alias of sl::VIEW::DEPTH. Type: sl::MAT_TYPE::U8_C4 | | DEPTH_BGR | | Depth image in BGR pixel format: Type: sl::MAT_TYPE::U8_C3 | | DEPTH_GRAY | | Depth image in gray scale: Type: sl::MAT_TYPE::U8_C1 | | CONFIDENCE_BGRA | | Alias of sl::VIEW::CONFIDENCE. Type: sl::MAT_TYPE::U8_C4 | | CONFIDENCE_BGR | | Confidence image in BGR pixel format: Type: sl::MAT_TYPE::U8_C3 | | CONFIDENCE_GRAY | | Confidence image in gray scale: Type: sl::MAT_TYPE::U8_C1 | | NORMALS_BGRA | | Alias of sl::VIEW::NORMALS. Type: sl::MAT_TYPE::U8_C4 | | NORMALS_BGR | | Normal image in BGR pixel format: Type: sl::MAT_TYPE::U8_C3 | | NORMALS_GRAY | | Normal image in gray scale: Type: sl::MAT_TYPE::U8_C1 | | DEPTH_RIGHT_BGRA | | Alias of sl::VIEW::DEPTH_RIGHT. Type: sl::MAT_TYPE::U8_C4 | | DEPTH_RIGHT_BGR | | Depth right image in BGR pixel format: Type: sl::MAT_TYPE::U8_C3 | | DEPTH_RIGHT_GRAY | | Depth right image in gray scale: Type: sl::MAT_TYPE::U8_C1 | | NORMALS_RIGHT_BGRA | | Alias of sl::VIEW::NORMALS_RIGHT. Type: sl::MAT_TYPE::U8_C4 | | NORMALS_RIGHT_BGR | | Normal right image in BGR pixel format: Type: sl::MAT_TYPE::U8_C3 | | NORMALS_RIGHT_GRAY | | Normal right image in gray scale: Type: sl::MAT_TYPE::U8_C1 | Lists available views. ### enum POSITIONAL_TRACKING_MODE | Enumerator | Value | Description | | ---------- | ----- | ----------- | | GEN_1 | | Default mode. Fast and stable mode. Requires depth computation. Less robust than GEN_3 | | GEN_2 | | | | 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]. | Lists the mode of positional tracking that can be used. ### enum AREA_EXPORTING_STATE | Enumerator | Value | Description | | ---------- | ----- | ----------- | | 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. | Lists the different states of spatial memory area export. ### enum SPATIAL_MAPPING_STATE | Enumerator | Value | Description | | ---------- | ----- | ----------- | | 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::enableSpatialMapping() 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::SpatialMappingParameters::MAPPING_RESOLUTION::LOW, low camera resolution (sl::RESOLUTION::VGA/SVGA or sl::RESOLUTION::HD720). | Lists the different states of spatial mapping. ### enum REGION_OF_INTEREST_AUTO_DETECTION_STATE | Enumerator | Value | Description | | ---------- | ----- | ----------- | | 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 | Lists the different states of region of interest auto detection. ### enum SVO_COMPRESSION_MODE | Enumerator | Value | Description | | ---------- | ----- | ----------- | | LOSSLESS | | PNG/ZSTD (lossless) CPU based compression. Average size: 42% of RAW | | H264 | | H264 (AVCHD) GPU based compression. Average size: 1% of RAW | | H265 | | H265 (HEVC) GPU based compression. Average size: 1% of RAW | | H264_LOSSLESS | | H264 Lossless GPU/Hardware based compression. Average size: 25% of RAW Provides a SSIM/PSNR result (vs RAW) >= 99.9%. | | H265_LOSSLESS | | H265 Lossless GPU/Hardware based compression. Average size: 25% of RAW Provides a SSIM/PSNR result (vs RAW) >= 99.9%. | 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. ### enum SVO_ENCODING_PRESET | Enumerator | Value | Description | | ---------- | ----- | ----------- | | DEFAULT | | Encoder default. Maps to NVENC P4 / V4L2 default. | | 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. | Lists available encoding presets for SVO recording. **Note**: Only applicable when SVO_COMPRESSION_MODE is H264 or H265 (lossy or lossless). The preset controls the speed/quality tradeoff of the hardware encoder. ### enum VOXELIZATION_MODE | Enumerator | Value | Description | | ---------- | ----- | ----------- | | FIXED | | No adaptation. VoxelMeasureParameters::voxel_size is used uniformly everywhere. | | STEREO_UNCERTAINTY | | Quadratic growth matching stereo depth noise: Z²/(f·B), scaled by VoxelMeasureParameters::resolution_scale . Voxels grow larger at distance where stereo depth precision is lower. | | LINEAR | | Linear growth with depth Z, scaled by VoxelMeasureParameters::resolution_scale . Suits sensors with linearly increasing noise (e.g. lidar, ToF). | Controls how voxel size adapts with depth in sl::Camera::retrieveVoxelMeasure. ### enum RAW_BUFFER_TYPE | Enumerator | Value | Description | | ---------- | ----- | ----------- | | UNKNOWN | 0| Unknown or uninitialized buffer type. | | NVBUFSURFACE | | NvBufSurface (Argus native buffer) | Lists the types of native raw buffers supported by RawBuffer. **Warning**: This is an advanced low-level API. Enabled by defining SL_ENABLE_ADVANCED_CAPTURE_API before including this header. Improper use can crash the Argus stack or destabilize the system. ### enum SENSOR_STATE | Enumerator | Value | Description | | ---------- | ----- | ----------- | | AVAILABLE | | The sensor can be opened by the ZED SDK. | | NOT_AVAILABLE | | The sensor is already opened and unavailable. | Lists possible sensor states. ### enum LIDAR_MEASURE | Enumerator | Value | Description | | ---------- | ----- | ----------- | | RANGE | | Range map (1 channel, float 32), similar to depth map but distance is real radial distance. Can be retrieved as a sl::Mat. | | RANGE2 | | Range map for the second return (1 channel, float 32). | | SIGNAL | | Signal intensity map (1 channel, float 32). | | SIGNAL2 | | Signal intensity map for the second return (1 channel, float 32). | | INTENSITY | | Intensity map (1 channel, float 32). | | REFLECTIVITY | | Reflectivity map (1 channel, float 32). | | REFLECTIVITY2 | | Reflectivity map for the second return (1 channel, float 32). | | NEAR_IR | | Near IR map (1 channel, float 32). | | XYZ | | Point cloud (3 channels, float 32). Contains X, Y, Z coordinates. | | XYZ_RANGE | | Point cloud with range (4 channels, float 32). Contains X, Y, Z coordinates and Range value. | | XYZ_RANGE2 | | Point cloud with range for second return (4 channels, float 32). | | XYZ_SIGNAL | | Point cloud with signal (4 channels, float 32). | | XYZ_SIGNAL2 | | Point cloud with signal for second return (4 channels, float 32). | | XYZ_INTENSITY | | Point cloud with intensity (4 channels, float 32). | | XYZ_REFLECTIVITY | | Point cloud with reflectivity (4 channels, float 32). | | XYZ_REFLECTIVITY2 | | Point cloud with reflectivity for second return (4 channels, float 32). | | XYZ_NEAR_IR | | Point cloud with near IR (4 channels, float 32). | | XYZ_RANGE_VIEW | | Point cloud with range view (4 channels, float 32). | | XYZ_RANGE2_VIEW | | Point cloud with range view for second return (4 channels, float 32). | | XYZ_SIGNAL_VIEW | | Point cloud with signal view (4 channels, float 32). | | XYZ_SIGNAL2_VIEW | | Point cloud with signal view for second return (4 channels, float 32). | | XYZ_INTENSITY_VIEW | | Point cloud with intensity view (4 channels, float 32). | | XYZ_REFLECTIVITY_VIEW | | Point cloud with reflectivity view (4 channels, float 32). | | XYZ_REFLECTIVITY2_VIEW | | Point cloud with reflectivity view for second return (4 channels, float 32). | | XYZ_NEAR_IR_VIEW | | Point cloud with near IR view (4 channels, float 32). | | RANGE_RAW | | Raw range in staggered format (F32_C1, meters). | | RANGE2_RAW | | Raw range for second return in staggered format (F32_C1, meters). | | SIGNAL_RAW | | Raw signal in staggered format (U16_C1, counts). | | SIGNAL2_RAW | | Raw signal for second return in staggered format (U16_C1, counts). | | REFLECTIVITY_RAW | | Raw reflectivity in staggered format (U16_C1, counts). | | REFLECTIVITY2_RAW | | Raw reflectivity for second return in staggered format (U16_C1, counts). | | NEAR_IR_RAW | | Raw near-IR in staggered format (U16_C1, counts). | Lists available object types that can be retrieved from the Lidar. ### enum LIDAR_VIEW | Enumerator | Value | Description | | ---------- | ----- | ----------- | | INTENSITY | | | | REFLECTIVITY | | | | DEPTH | | | | RANGE | | | | SIGNAL | | | | NEAR_IR | | | | RANGE2 | | | | SIGNAL2 | | | | REFLECTIVITY2 | | | Lists available view types that can be retrieved from the Lidar. ### enum VIEW_COLOR_MAP | Enumerator | Value | Description | | ---------- | ----- | ----------- | | AUTO | | | | GREY | | | | MAGMA | | | | INFERNO | | | | PLASMA | | | | VIRIDIS | | | | SPEZIA | | | | TURBO | | | | JET | | | | BONE | | | | GNUPLOT2 | | | Lists available colormaps for Lidar data visualization. ### enum LIDAR_MODE | Enumerator | Value | Description | | ---------- | ----- | ----------- | | AUTO | | | | MODE_512x10 | | | | MODE_1024x10 | | | | MODE_2048x10 | | | | MODE_512x20 | | | | MODE_1024x20 | | | Lists available Lidar modes (resolution and frequency). ### enum LIDAR_MULTICAST_MODE | Enumerator | Value | Description | | ---------- | ----- | ----------- | | OFF | | Disable multicast, force unicast mode. The sensor will stream data only to this client. If another client is already receiving, this will take over (disrupting the other client). | | AUTO | | Automatic multicast management (default). Behavior depends on current sensor state: - If InitLidarParameters::multicast_group is set and valid: enables multicast with that IP - If InitLidarParameters::multicast_group is set but invalid: returns [ERROR_CODE::CONFIGURATION_FALLBACK], uses current config - If sensor is already in multicast: joins existing group passively - If sensor is unicast and no other client connected: stays unicast - If sensor is unicast and another client connected: enables multicast to allow sharing. | | ON | | Force multicast mode. - If InitLidarParameters::multicast_group is set and valid: uses that IP - If InitLidarParameters::multicast_group is set but invalid: returns [ERROR_CODE::INVALID_FUNCTION_PARAMETERS] (hard fail) - If InitLidarParameters::multicast_group is empty: auto-selects a valid multicast IP (239.201.201.201) | Controls multicast streaming behavior for the Lidar sensor. Multicast allows multiple clients to receive data from the same sensor simultaneously. In unicast mode, only one client can receive data at a time. ### enum RECORDING_FORMAT | Enumerator | Value | Description | | ---------- | ----- | ----------- | | OSF | | | | PCAP | | | | PCD | | | | AUTO | | | Lists available recording formats for Lidar data. ### enum SENSORS_TYPE | Enumerator | Value | Description | | ---------- | ----- | ----------- | | CAMERA | | Standard ZED Camera (ZED 2, ZED 2i, ZED X, ZED X Mini). | | CAMERA_ONE | | ZED One Camera. | | LIDAR | | Lidar device. | Lists available sensor types managed by the Sensors class. ### enum SENSORS_ERROR_CODE | Enumerator | Value | Description | | ---------- | ----- | ----------- | | STALE_DATA | -8| In pipelined mode with DROP_STALE sync policy, the retrieved data is too old relative to the sync timestamp. The frame was not returned to avoid using outdated information. | | GNSS_DATA_NEED_FIX | -7| This is a warning message indicating an issue with the ingestGNSSData function call. The problem lies in the gnss_status field of the GNSSData parameter, which is currently set to UNKNOWN. To enhance the accuracy of the VPS (Visual Positioning System), it is essential to provide an appropriate value for this field. To rectify this issue, please consider setting the gnss_status field to a valid value that reflects the status of your GNSS sensor. If your GNSS sensor is unable to output a status, it is recommended to set the gnss_status field to [sl::GNSS_STATUS::SINGLE]. | | INVALID_COVARIANCE | -6| This is a warning message notifying you about an issue encountered while ingesting GNSSData into the Fusion system. The problem lies in the very low covariance value provided. To ensure stability and prevent potential issues, the system will automatically clamp this covariance value. | | INVALID_TIMESTAMP | -5| You have attempted to ingest GNSSData into the Fusion system with an invalid timestamp. It is essential to ensure that the timestamp of your GNSSData is set correctly. This issue may arise from a unit error in the ingested timestamp, such as providing the timestamp in microseconds instead of nanoseconds. | | CONFIGURATION_FALLBACK | -4| The operation could not proceed with the target configuration but did success with a fallback. | | MOTION_SENSORS_DATA_REQUIRED | -3| The input data does not contains the high frequency motion sensors data (IMU), this is usually because it requires newer SVO/Streaming. In order to work this modules needs inertial data present in it input. | | CORRUPTED_FRAME | -2| The image is corrupted with invalid colors (green/purple images). This indicates a serious hardware or driver issue. | | SENSOR_REBOOTING | -1| The sensor is currently rebooting. | | SUCCESS | 0| Standard code for successful behavior. | | FAILURE | 1| Standard code for unsuccessful behavior. | | NO_GPU_COMPATIBLE | 2| No GPU found or CUDA capability of the device is not supported. | | NOT_ENOUGH_GPU_MEMORY | 3| 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). | | SENSOR_NOT_DETECTED | 4| No sensor was detected. | | MOTION_SENSORS_NOT_INITIALIZED | 5| The MCU that controls the motion sensors module (IMU) 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`. | | MOTION_SENSORS_NOT_AVAILABLE | 6| A camera with motion sensors is detected but the motion sensors (IMU, barometer, ...) cannot be opened. Only the MODEL::ZED does not have motion sensors. Unplug/replug is required. | | INVALID_RESOLUTION | 7| In case of invalid resolution parameter, such as an upsize beyond the original image size in Camera::retrieveImage. | | LOW_USB_BANDWIDTH | 8| 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 | 9| 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 | 10| The calibration file is not valid. Try to download the factory calibration file or recalibrate your camera using **ZED Calibration**. | | INVALID_SVO_FILE | 11| The provided SVO file is not valid. | | SVO_RECORDING_ERROR | 12| An error occurred while trying to record an SVO (not enough free storage, invalid file, ...). | | SVO_UNSUPPORTED_COMPRESSION | 13| An SVO related error, occurs when NVIDIA based compression cannot be loaded. | | END_OF_SVOFILE_REACHED | 14| SVO end of file has been reached. No frame will be available until the SVO position is reset. | | INVALID_COORDINATE_SYSTEM | 15| The requested coordinate system is not available. | | INVALID_FIRMWARE | 16| The firmware of the camera is out of date. Update to the latest version. | | INVALID_FUNCTION_PARAMETERS | 17| Invalid parameters have been given for the function. | | CUDA_ERROR | 18| A CUDA error has been detected in the process, in Camera.grab() or Camera.retrieveXXX() only. Activate verbose in Camera.open() for more info. | | SENSOR_NOT_INITIALIZED | 19| The sensor is not initialized. Probably a missing call to open the sensor. | | NVIDIA_DRIVER_OUT_OF_DATE | 20| Your NVIDIA driver is too old and not compatible with your current CUDA version. | | INVALID_FUNCTION_CALL | 21| The call of the function is not valid in the current context. Could be a missing call of Camera.open(). | | CORRUPTED_SDK_INSTALLATION | 22| 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 | 23| The installed ZED SDK is incompatible with the one used to compile the program. | | INVALID_AREA_FILE | 24| The given area file does not exist. Check the path. | | INCOMPATIBLE_AREA_FILE | 25| The area file does not contain enough data to be used or the DEPTH_MODE used during the creation of the area file is different from the one currently set. | | SENSOR_FAILED_TO_SETUP | 26| Failed to open the sensor at the proper resolution. Try another resolution or make sure that the UVC driver is properly installed. | | SENSOR_DETECTION_ISSUE | 27| Your sensor can not be opened. Try replugging it to another port or flipping the USB-C connector (if there is one). | | CANNOT_START_SENSOR_STREAM | 28| Cannot start the sensor stream. Make sure your sensor is not already used by another process or blocked by firewall or antivirus. | | NO_GPU_DETECTED | 29| No GPU found. CUDA is unable to list it. Can be a driver/reboot issue. | | PLANE_NOT_FOUND | 30| 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_SENSOR | 31| The module you try to use is not compatible with your sensor MODEL. | | MOTION_SENSORS_REQUIRED | 32| The module needs the sensors to be enabled (see InitParameters::sensors_required). | | MODULE_NOT_COMPATIBLE_WITH_CUDA_VERSION | 33| The module needs a newer version of CUDA. | | DRIVER_FAILURE | 34| The drivers initialization has failed. When using gmsl cameras, try restarting with sudo systemctl restart zed_x_daemon.service | | CAMERA_EXCEEDS_BANDWIDTH | 35| The camera configuration exceeds available PHY CSI bandwidth (GMSL). Reduce resolution/FPS or adjust hardware configuration. | Lists error codes in the Sensors SDK. ### enum UNIT | Enumerator | Value | Description | | ---------- | ----- | ----------- | | 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) | Lists available units for measures. ### enum COORDINATE_SYSTEM | Enumerator | Value | Description | | ---------- | ----- | ----------- | | IMAGE | | Standard coordinates system in computer vision. Used in OpenCV: see [here](http://docs.opencv.org/2.4/modules/calib3d/doc/camera_calibration_and_3d_reconstruction.html). | | 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). | Lists available coordinates systems for positional tracking and 3D measures. !CoordinateSystem.webp ### enum ERROR_CODE | Enumerator | Value | Description | | ---------- | ----- | ----------- | | SENSOR_CONFIGURATION_CHANGED | -6| The sensor's configuration (mode, multicast, etc.) was changed externally while streaming. If auto_recovery_on_config_change is enabled, the SDK will automatically reconnect. This warning code is returned once after successful recovery. | | POTENTIAL_CALIBRATION_ISSUE | -5| The camera has a potential calibration issue | | CONFIGURATION_FALLBACK | -4| The operation could not proceed with the target configuration but did success with a fallback. | | SENSORS_DATA_REQUIRED | -3| 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 | -2| The image is corrupted with invalid colors (green/purple images). This indicates a serious hardware or driver issue. Check camera connection and drivers. | | CAMERA_REBOOTING | -1| The camera is currently rebooting. | | SUCCESS | 0| Standard code for successful behavior. | | FAILURE | 1| Standard code for unsuccessful behavior. | | NO_GPU_COMPATIBLE | 2| No GPU found or CUDA capability of the device is not supported. | | NOT_ENOUGH_GPU_MEMORY | 3| 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 | 4| No camera was detected. | | SENSORS_NOT_INITIALIZED | 5| 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 | 6| 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 | 7| In case of invalid resolution parameter, such as an upsize beyond the original image size in Camera::retrieveImage. | | LOW_USB_BANDWIDTH | 8| 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 | 9| 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 | 10| The calibration file is not valid. Try to download the factory calibration file or recalibrate your camera using **ZED Calibration**. | | INVALID_SVO_FILE | 11| The provided SVO file is not valid. | | SVO_RECORDING_ERROR | 12| An error occurred while trying to record an SVO (not enough free storage, invalid file, ...). | | SVO_UNSUPPORTED_COMPRESSION | 13| An SVO related error, occurs when NVIDIA based compression cannot be loaded. | | END_OF_SVOFILE_REACHED | 14| SVO end of file has been reached. No frame will be available until the SVO position is reset. | | INVALID_COORDINATE_SYSTEM | 15| The requested coordinate system is not available. | | INVALID_FIRMWARE | 16| The firmware of the camera is out of date. Update to the latest version. | | INVALID_FUNCTION_PARAMETERS | 17| Invalid parameters have been given for the function. | | CUDA_ERROR | 18| A CUDA error has been detected in the process, in Camera.grab() or Camera.retrieveXXX() only. Activate verbose in Camera.open() for more info. | | CAMERA_NOT_INITIALIZED | 19| The ZED SDK is not initialized. Probably a missing call to Camera.open(). | | NVIDIA_DRIVER_OUT_OF_DATE | 20| Your NVIDIA driver is too old and not compatible with your current CUDA version. | | INVALID_FUNCTION_CALL | 21| The call of the function is not valid in the current context. Could be a missing call of Camera.open(). | | CORRUPTED_SDK_INSTALLATION | 22| 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 | 23| The installed ZED SDK is incompatible with the one used to compile the program. | | INVALID_AREA_FILE | 24| The given area file does not exist. Check the path. | | INCOMPATIBLE_AREA_FILE | 25| The area file does not contain enough data to be used or the DEPTH_MODE used during the creation of the area file is different from the one currently set. | | CAMERA_FAILED_TO_SETUP | 26| 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 | 27| 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 | 28| 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 | 29| No GPU found. CUDA is unable to list it. Can be a driver/reboot issue. | | PLANE_NOT_FOUND | 30| 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 | 31| The module you try to use is not compatible with your camera MODEL. | | MOTION_SENSORS_REQUIRED | 32| The module needs the sensors to be enabled (see InitParameters::sensors_required). | | MODULE_NOT_COMPATIBLE_WITH_CUDA_VERSION | 33| The module needs a newer version of CUDA. | | DRIVER_FAILURE | 34| The drivers initialization has failed. When using gmsl cameras, try restarting with sudo systemctl restart zed_x_daemon.service | | CAMERA_EXCEEDS_BANDWIDTH | 35| The camera configuration exceeds available PHY CSI bandwidth (GMSL). Reduce resolution/FPS or adjust hardware configuration. | Lists error codes in the ZED SDK. ### enum MODEL | Enumerator | Value | Description | | ---------- | ----- | ----------- | | ZED | 0| ZED camera model | | ZED_M | 1| ZED Mini (ZED M) camera model | | ZED2 | 2| ZED 2 camera model | | ZED2i | 3| ZED 2i camera model | | ZED_X | 4| ZED X camera model (120mm baseline) with dual global shutter AR0234 sensor | | ZED_XM | 5| ZED X Mini (50mm baseline) camera model with dual global shutter AR0234 sensor | | ZED_X_HDR | 6| ZED X HDR camera model (120mm baseline) with dual HDR rolling shutter ISX031 sensor | | ZED_X_HDR_MINI | 7| ZED X HDR mini camera model (50mm baseline) with dual HDR rolling shutter ISX031 sensor | | ZED_X_HDR_MAX | 8| ZED X HDR Max camera model (170mm baseline) with dual HDR rolling shutter ISX031 sensor | | ZED_X_NANO | 9| ZED X Nano (18mm baseline) camera model with dual global shutter AR0234 sensor | | VIRTUAL_ZED_X | 11| Virtual ZED-X generated from 2 ZED-XOne (Using ZED Media Server) | | ZED_XONE_GS | 30| ZED X One with global shutter AR0234 sensor | | ZED_XONE_UHD | 31| ZED X One with 4K rolling shutter IMX678 sensor | | ZED_XONE_HDR | 32| ZED X One with HDR rolling shutter ISX031 sensor | Lists ZED camera model. ### enum INPUT_TYPE | Enumerator | Value | Description | | ---------- | ----- | ----------- | | USB | | USB input mode | | SVO | | SVO file input mode | | STREAM | | STREAM input mode (requires to use enableStreaming() / disableStreaming()" on the "sender" side) | | GMSL | | GMSL input mode (only on NVIDIA Jetson) | Lists available input types in the ZED SDK. ### enum CAMERA_STATE | Enumerator | Value | Description | | ---------- | ----- | ----------- | | AVAILABLE | | The camera can be opened by the ZED SDK. | | NOT_AVAILABLE | | The camera is already opened and unavailable. | Lists possible camera states. ### enum STREAMING_CODEC | Enumerator | Value | Description | | ---------- | ----- | ----------- | | H264 | | AVCHD/H264 encoding | | H265 | | HEVC/H265 encoding | Lists the different encoding types for image streaming. ### enum SENSOR_TYPE | Enumerator | Value | Description | | ---------- | ----- | ----------- | | 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. | Lists available sensor types. **Note**: Sensors are not available on sl::MODEL::ZED. ### enum SENSORS_UNIT | Enumerator | Value | Description | | ---------- | ----- | ----------- | | 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) | Lists available measurement units of onboard sensors. **Note**: Sensors are not available on sl::MODEL::ZED. ### enum BUS_TYPE | Enumerator | Value | Description | | ---------- | ----- | ----------- | | USB | | USB input mode | | GMSL | | GMSL input mode | | AUTO | | Automatically select the input type. Trying first for available USB cameras, then GMSL. | Lists available LIVE input type in the ZED SDK. ### enum OBJECT_DETECTION_MODEL | Enumerator | Value | Description | | ---------- | ----- | ----------- | | MULTI_CLASS_BOX_FAST | | Any objects, bounding box based. | | MULTI_CLASS_BOX_MEDIUM | | Any objects, bounding box based, compromise between accuracy and speed. | | MULTI_CLASS_BOX_ACCURATE | | Any objects, bounding box based, more accurate but slower than the base model. | | 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. | | CUSTOM_YOLOLIKE_BOX_OBJECTS | | For internal inference using your own custom YOLO-like model. This mode requires a onnx file to be passed in the ObjectDetectionParameters. This model will be used for inference. | Lists available models for the object detection module. ### enum BODY_TRACKING_MODEL | Enumerator | Value | Description | | ---------- | ----- | ----------- | | HUMAN_BODY_FAST | | Keypoints based, specific to human skeleton, real time performance even on Jetson or low end GPU cards. | | HUMAN_BODY_MEDIUM | | Keypoints based, specific to human skeleton, compromise between accuracy and speed. | | HUMAN_BODY_ACCURATE | | Keypoints based, specific to human skeleton, state of the art accuracy, requires powerful GPU. | Lists available models for the body tracking module. ### enum AI_MODELS | Enumerator | Value | Description | | ---------- | ----- | ----------- | | 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]](OBJECT_DETECTION_MODEL) | | 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]](OBJECT_DETECTION_MODEL) | | REID_ASSOCIATION | | Related to sl::BatchParameters.enable | | NEURAL_LIGHT_DEPTH | | Related to sl::DEPTH_MODE::NEURAL_LIGHT | | NEURAL_DEPTH | | Related to sl::DEPTH_MODE::NEURAL | | NEURAL_PLUS_DEPTH | | Related to sl::DEPTH_MODE::NEURAL_PLUS | Lists available AI models. ### enum MEM | Enumerator | Value | Description | | ---------- | ----- | ----------- | | CPU | 1| Data will be stored on the CPU (processor side). | | GPU | 2| Data will be stored on the GPU (graphic card side). | | BOTH | 3| Data will be stored on the GPU and CPU. | | LAST | 4| | Lists available memory type. ### enum COPY_TYPE | Enumerator | Value | Description | | ---------- | ----- | ----------- | | CPU_CPU | | Copy data from CPU to CPU. | | CPU_GPU | | Copy data from CPU to GPU. | | GPU_GPU | | Copy data from GPU to GPU. | | GPU_CPU | | Copy data from GPU to CPU. | Lists available copy operation on sl::Mat. ### enum MAT_TYPE | Enumerator | Value | Description | | ---------- | ----- | ----------- | | 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 | Lists available sl::Mat formats. **Note**: * sl::Mat type depends on image or measure type. * For the dependencies, see sl::VIEW and sl::MEASURE. ### enum MODULE | Enumerator | Value | Description | | ---------- | ----- | ----------- | | ALL | 0| All modules | | DEPTH | 1| | | POSITIONAL_TRACKING | 2| | | OBJECT_DETECTION | 3| | | BODY_TRACKING | 4| | | SPATIAL_MAPPING | 5| | | LAST | 6| | Lists available modules. ### enum OBJECT_CLASS | Enumerator | Value | Description | | ---------- | ----- | ----------- | | PERSON | 0| For people detection | | VEHICLE | 1| For vehicle detection (cars, trucks, buses, motorcycles, etc.) | | BAG | 2| For bag detection (backpack, handbag, suitcase, etc.) | | ANIMAL | 3| For animal detection (cow, sheep, horse, dog, cat, bird, etc.) | | ELECTRONICS | 4| For electronic device detection (cellphone, laptop, etc.) | | FRUIT_VEGETABLE | 5| For fruit and vegetable detection (banana, apple, orange, carrot, etc.) | | SPORT | 6| For sport-related object detection (sport ball, etc.) | Lists available object classes. ### enum OBJECT_SUBCLASS | Enumerator | Value | Description | | ---------- | ----- | ----------- | | PERSON | 0| PERSON | | PERSON_HEAD | 22| PERSON | | BICYCLE | 1| VEHICLE | | CAR | 2| VEHICLE | | MOTORBIKE | 3| VEHICLE | | BUS | 4| VEHICLE | | TRUCK | 5| VEHICLE | | BOAT | 6| VEHICLE | | BACKPACK | 7| BAG | | HANDBAG | 8| BAG | | SUITCASE | 9| BAG | | BIRD | 10| ANIMAL | | CAT | 11| ANIMAL | | DOG | 12| ANIMAL | | HORSE | 13| ANIMAL | | SHEEP | 14| ANIMAL | | COW | 15| ANIMAL | | CELLPHONE | 16| ELECTRONICS | | LAPTOP | 17| ELECTRONICS | | BANANA | 18| FRUIT_VEGETABLE | | APPLE | 19| FRUIT_VEGETABLE | | ORANGE | 20| FRUIT_VEGETABLE | | CARROT | 21| FRUIT_VEGETABLE | | SPORTSBALL | 23| SPORT | | MACHINERY | 24| VEHICLE | 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). ### enum OBJECT_TRACKING_STATE | Enumerator | Value | Description | | ---------- | ----- | ----------- | | 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.retrieveObjects(). | Lists the different states of object tracking. ### enum OBJECT_ACTION_STATE | Enumerator | Value | Description | | ---------- | ----- | ----------- | | IDLE | 0| The object is staying static. | | MOVING | 1| The object is moving. | Lists the different states of an object's actions. ### enum OBJECT_FILTERING_MODE | Enumerator | Value | Description | | ---------- | ----- | ----------- | | 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. | Lists supported bounding box preprocessing. ### enum OBJECT_ACCELERATION_PRESET | Enumerator | Value | Description | | ---------- | ----- | ----------- | | 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). | Lists of supported presets for maximum acceleration allowed for a given tracked object. ### enum INFERENCE_PRECISION | Enumerator | Value | Description | | ---------- | ----- | ----------- | | FP32 | 0| | | FP16 | 1| | | INT8 | 2| | Report the actual inference precision used. ### enum BODY_FORMAT | Enumerator | Value | Description | | ---------- | ----- | ----------- | | BODY_18 | | 18-keypoint model Basic body model | | BODY_34 | | 34-keypoint model | | BODY_38 | | 38-keypoint model Including simplified face, hands and feet. | Lists supported skeleton body models. ### enum BODY_KEYPOINTS_SELECTION | Enumerator | Value | Description | | ---------- | ----- | ----------- | | FULL | | Full keypoint model. | | UPPER_BODY | | Upper body keypoint model Will output only upper body (from hip). | Lists supported models for skeleton keypoints selection. ### enum REFERENCE_FRAME | Enumerator | Value | Description | | ---------- | ----- | ----------- | | WORLD | | The transform of sl::Pose will contain the motion with reference to the world frame (previously called PATH). | | CAMERA | | The transform of sl::Pose will contain the motion with reference to the previous camera frame (previously called POSE). | Lists possible types of position matrix used to store camera path and pose. ### enum BODY_18_PARTS | Enumerator | Value | Description | | ---------- | ----- | ----------- | | NOSE | 0| 0 | | NECK | 1| 1 | | RIGHT_SHOULDER | 2| 2 | | RIGHT_ELBOW | 3| 3 | | RIGHT_WRIST | 4| 4 | | LEFT_SHOULDER | 5| 5 | | LEFT_ELBOW | 6| 6 | | LEFT_WRIST | 7| 7 | | RIGHT_HIP | 8| 8 | | RIGHT_KNEE | 9| 9 | | RIGHT_ANKLE | 10| 10 | | LEFT_HIP | 11| 11 | | LEFT_KNEE | 12| 12 | | LEFT_ANKLE | 13| 13 | | RIGHT_EYE | 14| 14 | | LEFT_EYE | 15| 15 | | RIGHT_EAR | 16| 16 | | LEFT_EAR | 17| 17 | Semantic of human body parts and order of sl::BodyData::keypoint for sl::BODY_FORMAT::BODY_18. ### enum BODY_34_PARTS | Enumerator | Value | Description | | ---------- | ----- | ----------- | | PELVIS | 0| 0 | | NAVAL_SPINE | 1| 1 | | CHEST_SPINE | 2| 2 | | NECK | 3| 3 | | LEFT_CLAVICLE | 4| 4 | | LEFT_SHOULDER | 5| 5 | | LEFT_ELBOW | 6| 6 | | LEFT_WRIST | 7| 7 | | LEFT_HAND | 8| 8 | | LEFT_HANDTIP | 9| 9 | | LEFT_THUMB | 10| 10 | | RIGHT_CLAVICLE | 11| 11 | | RIGHT_SHOULDER | 12| 12 | | RIGHT_ELBOW | 13| 13 | | RIGHT_WRIST | 14| 14 | | RIGHT_HAND | 15| 15 | | RIGHT_HANDTIP | 16| 16 | | RIGHT_THUMB | 17| 17 | | LEFT_HIP | 18| 18 | | LEFT_KNEE | 19| 19 | | LEFT_ANKLE | 20| 20 | | LEFT_FOOT | 21| 21 | | RIGHT_HIP | 22| 22 | | RIGHT_KNEE | 23| 23 | | RIGHT_ANKLE | 24| 24 | | RIGHT_FOOT | 25| 25 | | HEAD | 26| 26 | | NOSE | 27| 27 | | LEFT_EYE | 28| 28 | | LEFT_EAR | 29| 29 | | RIGHT_EYE | 30| 30 | | RIGHT_EAR | 31| 31 | | LEFT_HEEL | 32| 32 | | RIGHT_HEEL | 33| 33 | Semantic of human body parts and order of sl::BodyData::keypoint for sl::BODY_FORMAT::BODY_34. ### enum BODY_38_PARTS | Enumerator | Value | Description | | ---------- | ----- | ----------- | | PELVIS | 0| 0 | | SPINE_1 | 1| 1 | | SPINE_2 | 2| 2 | | SPINE_3 | 3| 3 | | NECK | 4| 4 | | NOSE | 5| 5 | | LEFT_EYE | 6| 6 | | RIGHT_EYE | 7| 7 | | LEFT_EAR | 8| 8 | | RIGHT_EAR | 9| 9 | | LEFT_CLAVICLE | 10| 10 | | RIGHT_CLAVICLE | 11| 11 | | LEFT_SHOULDER | 12| 12 | | RIGHT_SHOULDER | 13| 13 | | LEFT_ELBOW | 14| 14 | | RIGHT_ELBOW | 15| 15 | | LEFT_WRIST | 16| 16 | | RIGHT_WRIST | 17| 17 | | LEFT_HIP | 18| 18 | | RIGHT_HIP | 19| 19 | | LEFT_KNEE | 20| 20 | | RIGHT_KNEE | 21| 21 | | LEFT_ANKLE | 22| 22 | | RIGHT_ANKLE | 23| 23 | | LEFT_BIG_TOE | 24| 24 | | RIGHT_BIG_TOE | 25| 25 | | LEFT_SMALL_TOE | 26| 26 | | RIGHT_SMALL_TOE | 27| 27 | | LEFT_HEEL | 28| 28 | | RIGHT_HEEL | 29| 29 | | LEFT_HAND_THUMB_4 | 30| 30 | | RIGHT_HAND_THUMB_4 | 31| 31 | | LEFT_HAND_INDEX_1 | 32| 32 | | RIGHT_HAND_INDEX_1 | 33| 33 | | LEFT_HAND_MIDDLE_4 | 34| 34 | | RIGHT_HAND_MIDDLE_4 | 35| 35 | | LEFT_HAND_PINKY_1 | 36| 36 | | RIGHT_HAND_PINKY_1 | 37| 37 | Semantic of human body parts and order of sl::BodyData::keypoint for sl::BODY_FORMAT::BODY_38. ### enum TIME_REFERENCE | Enumerator | Value | Description | | ---------- | ----- | ----------- | | 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. | Lists possible time references for timestamps or data. ### enum POSITIONAL_TRACKING_STATE | Enumerator | Value | Description | | ---------- | ----- | ----------- | | SEARCHING | | \warn 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. | Lists the different states of positional tracking. ### enum ODOMETRY_STATUS | Enumerator | Value | Description | | ---------- | ----- | ----------- | | OK | 0| The positional tracking module successfully tracked from the previous frame to the current frame. | | UNAVAILABLE | 1| The positional tracking module cannot track the current frame. | | INSUFFICIENT_FEATURES | 2| The positional tracking failed to track the current frame because it could not find enought features. | | LAST | | | Report the status of current odom tracking. ### enum SPATIAL_MEMORY_STATUS | Enumerator | Value | Description | | ---------- | ----- | ----------- | | OK | 0| Deprecated: This state is no longer in use for GEN_3. | | LOOP_CLOSED | 1| Displayed whenever the system has found a loop closure, relocalized within the area map or corrected after a sudden localization loss. | | SEARCHING | 2| Deprecated: This state is no longer in use for GEN_3. | | OFF | 3| Displayed when the spatial memory is turned off. | | INITIALIZING | 4| 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. | | KNOWN_MAP | 5| Displayed when the camera is localized within the loaded area map. | | MAP_UPDATE | 6| 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. | | LOST | 7| 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. | | NOT_ENOUGH_MEMORY_FOR_TRACKING | 8| Displayed when there is not enough memory to continue tracking. | | LAST | | | Report the status of current map tracking. ### enum POSITIONAL_TRACKING_FUSION_STATUS | Enumerator | Value | Description | | ---------- | ----- | ----------- | | VISUAL_INERTIAL | 0| | | VISUAL | 1| | | INERTIAL | 2| | | GNSS | 3| | | VISUAL_INERTIAL_GNSS | 4| | | VISUAL_GNSS | 5| | | INERTIAL_GNSS | 6| | | UNAVAILABLE | 7| | | LAST | | | Report the status of the positional tracking fusion. ### enum POSITION_TYPE | Enumerator | Value | Description | | ---------- | ----- | ----------- | | RAW | 0| The output position will be the raw position data. | | FUSION | 1| The output position will be the fused position projected into the requested camera repository. | Lists the types of possible position outputs. ### enum GNSS_STATUS | Enumerator | Value | Description | | ---------- | ----- | ----------- | | UNKNOWN | 0| No GNSS fix data is available. | | SINGLE | 1| Single Point Positioning. | | DGNSS | 2| Differential GNSS. | | PPS | 5| Precise Positioning Service. | | RTK_FLOAT | 4| Real Time Kinematic Float. | | RTK_FIX | 3| Real Time Kinematic Fixed. | | LAST | | | Class representing the status of the of GNSS signal. ### enum GNSS_MODE | Enumerator | Value | Description | | ---------- | ----- | ----------- | | UNKNOWN | 0| No GNSS fix data is available. | | NO_FIX | 1| No GNSS fix is available. | | FIX_2D | 2| 2D GNSS fix, providing latitude and longitude coordinates but without altitude information. | | FIX_3D | 3| 3D GNSS fix, providing latitude, longitude, and altitude coordinates. | | LAST | | | Class representing the mode of GNSS signal. ### enum GNSS_FUSION_STATUS | Enumerator | Value | Description | | ---------- | ----- | ----------- | | OK | 0| The GNSS fusion module is calibrated and working successfully. | | OFF | 1| The GNSS fusion module is not enabled. | | CALIBRATION_IN_PROGRESS | 2| Calibration of the GNSS/VIO fusion module is in progress. | | RECALIBRATION_IN_PROGRESS | 3| Re-alignment of GNSS/VIO data is in progress, leading to potentially inaccurate global position. | | LAST | | | Class containing the current GNSS fusion status. ### enum MESH_FILE_FORMAT | Enumerator | Value | Description | | ---------- | ----- | ----------- | | 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). | Lists available mesh file formats. ### enum MESH_TEXTURE_FORMAT | Enumerator | Value | Description | | ---------- | ----- | ----------- | | RGB | | The texture will be on 3 channels. | | RGBA | | The texture will be on 4 channels. | Lists available mesh texture formats. ### enum PLANE_TYPE | Enumerator | Value | Description | | ---------- | ----- | ----------- | | HORIZONTAL | | Horizontal plane, such as a tabletop, floor, etc. | | VERTICAL | | Vertical plane, such as a wall. | | UNKNOWN | | Unknown plane orientation. | Lists the available plane types detected based on the orientation. ### enum FUSION_REFERENCE_FRAME | Enumerator | Value | Description | | ---------- | ----- | ----------- | | WORLD | 0| The world frame is the reference frame of the world according to the fused positional Tracking | | BASELINK | 1| The base link frame is the reference frame where camera calibration is given | Enum to define the reference frame of the fusion SDK. ### enum FUSION_ERROR_CODE | Enumerator | Value | Description | | ---------- | ----- | ----------- | | FUSION_INCONSISTENT_FPS | -5| Significant differences observed between sender's FPS. Fusion quality will be affected. | | FUSION_FPS_TOO_LOW | -4| Fusion FPS is too low because at least one sender has an FPS lower than 10 FPS. Fusion quality will be affected. | | INVALID_TIMESTAMP | -3| You have attempted to ingest GNSSData into the Fusion system with an invalid timestamp. It is essential to ensure that the timestamp of your GNSSData is set correctly. This issue may arise from a unit error in the ingested timestamp, such as providing the timestamp in microseconds instead of nanoseconds. | | INVALID_COVARIANCE | -2| This is a warning message notifying you about an issue encountered while ingesting GNSSData into the Fusion system. The problem lies in the very low covariance value provided. To ensure stability and prevent potential issues, the system will automatically clamp this covariance value. | | NO_NEW_DATA_AVAILABLE | -1| All data from all sources has been consumed. No new data is available for processing. | | SUCCESS | 0| Standard code indicating successful behavior. | | GNSS_DATA_NEED_FIX | 1| This is a warning message indicating an issue with the ingestGNSSData function call. The problem lies in the gnss_status field of the GNSSData parameter, which is currently set to UNKNOWN. To enhance the accuracy of the VPS (Visual Positioning System), it is essential to provide an appropriate value for this field. To rectify this issue, please consider setting the gnss_status field to a valid value that reflects the status of your GNSS sensor. If your GNSS sensor is unable to output a status, it is recommended to set the gnss_status field to [sl::GNSS_STATUS::SINGLE]. | | GNSS_DATA_COVARIANCE_MUST_VARY | 2| It appears that you have made multiple calls to the ingestGNSSData function using the same GNSSData covariance. This warning is intended to prevent users from repeatedly ingesting a fixed or manually crafted covariance. | | BODY_FORMAT_MISMATCH | 3| Senders are using different body formats. Please use the same body format. | | MODULE_NOT_ENABLED | 4| The following module is not enabled. Please enable it to proceed. | | SOURCE_MISMATCH | 5| Some sources are provided by SVO and others by LIVE stream. | | CONNECTION_TIMED_OUT | 6| Connection timed out. Unable to reach the sender. Verify the sender's IP address and port. | | MEMORY_ALREADY_USED | 7| Intra-process shared memory allocation issue. Multiple connections to the same data. Check memory usage. | | INVALID_IP_ADDRESS | 8| The provided IP address format is incorrect. Please provide a valid IP address in the format 'a.b.c.d'. | | FAILURE | 9| Standard code indicating unsuccessful behavior. | Lists the types of error that can be raised by the Fusion. ### enum SENDER_ERROR_CODE | Enumerator | Value | Description | | ---------- | ----- | ----------- | | GRAB_ERROR | -3| | | INCONSISTENT_FPS | -2| | | FPS_TOO_LOW | -1| The frame rate of the sender is lower than 10 FPS. Check sender's settings and performance. | | SUCCESS | 0| | | DISCONNECTED | 1| | Lists the types of error that can be raised during the Fusion by senders. ### typedef CameraGroupID ```cpp typedef std::string CameraGroupID; ``` ### typedef SensorID ```cpp typedef std::string SensorID; ``` ## Functions Documentation ### function operator< ```cpp inline bool operator<( const Timestamp & lhs, const Timestamp & rhs ) ``` ### function operator> ```cpp inline bool operator>( const Timestamp & lhs, const Timestamp & rhs ) ``` ### function operator<= ```cpp inline bool operator<=( const Timestamp & lhs, const Timestamp & rhs ) ``` ### function operator>= ```cpp inline bool operator>=( const Timestamp & lhs, const Timestamp & rhs ) ``` ### function operator== ```cpp inline bool operator==( const Timestamp & lhs, const Timestamp & rhs ) ``` ### function operator!= ```cpp inline bool operator!=( const Timestamp & lhs, const Timestamp & rhs ) ``` ### function operator+ ```cpp inline Timestamp operator+( Timestamp lhs, const Timestamp & rhs ) ``` ### function operator- ```cpp inline Timestamp operator-( Timestamp lhs, const Timestamp & rhs ) ``` ### function operator/ ```cpp inline Timestamp operator/( Timestamp lhs, const Timestamp & rhs ) ``` ### function operator* ```cpp inline Timestamp operator*( Timestamp lhs, const Timestamp & rhs ) ``` ### function toString ```cpp * toString( const FLIP_MODE & flip_mode ) ``` ### function operator<< ```cpp inline ::std::ostream & operator<<( ::std::ostream & os, const FLIP_MODE & flip_mode ) ``` ### function getResolution ```cpp sl::Resolution getResolution( RESOLUTION resolution ) ``` Gets the corresponding sl::Resolution from an sl::RESOLUTION. **Parameters**: * **resolution** : The wanted sl::RESOLUTION. **Return**: The sl::Resolution corresponding to sl::RESOLUTION given as argument. ### function toString ```cpp * toString( const SVO_COMPRESSION_MODE & svo_compression ) ``` ### function fromString ```cpp bool fromString( const sl::String & svo_compression_str, SVO_COMPRESSION_MODE & svo_compression ) ``` ### function operator<< ```cpp inline ::std::ostream & operator<<( ::std::ostream & os, const SVO_COMPRESSION_MODE & svo_compression ) ``` ### function toString ```cpp * toString( const SVO_ENCODING_PRESET & preset ) ``` ### function fromString ```cpp bool fromString( const sl::String & preset_str, SVO_ENCODING_PRESET & preset ) ``` ### function operator<< ```cpp inline ::std::ostream & operator<<( ::std::ostream & os, const SVO_ENCODING_PRESET & preset ) ``` ### function setEnvironmentVariable ```cpp void setEnvironmentVariable( const sl::String & env_var_name, const sl::String & value ) ``` ### function getAvailableCameraFPS ```cpp inline const std::vector< int > & getAvailableCameraFPS() ``` 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. ### function isAvailable ```cpp bool isAvailable( const sl::RESOLUTION resolution, const sl::MODEL camera_model ) ``` Test if a specific resolution is available for the specified camera model. **Parameters**: * **resolution** : The wanted resolution. * **camera_model** : The wanted camera model. **Return**: True if the resolution is available for the camera model, false otherwise. ### function isAvailable ```cpp bool isAvailable( const int fps, const sl::RESOLUTION resolution, const sl::MODEL camera_model ) ``` Test if a specific resolution/fps combination is available for the specified camera model. **Parameters**: * **fps** : The wanted fps. * **resolution** : The wanted resolution. * **camera_model** : The wanted camera model. **Return**: True if the resolution is available for the camera model, false otherwise. ### function supportHDR ```cpp bool supportHDR( const sl::RESOLUTION resolution, const sl::MODEL camera_model ) ``` Test if the HDR mode can be activated at a specific resolution for the specified camera model. **Parameters**: * **resolution** : The wanted resolution. * **camera_model** : The wanted camera model. **Return**: True if the resolution is available for the camera model, false otherwise. ### function checkAIModelStatus ```cpp AI_Model_status checkAIModelStatus( AI_MODELS model, int gpu_id =0 ) ``` 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. ### function downloadAIModel ```cpp ERROR_CODE downloadAIModel( sl::AI_MODELS model, int gpu_id =0 ) ``` Downloads the requested model. **Return**: sl::ERROR_CODE::SUCCESS if the model is already download. ### function optimizeAIModel ```cpp ERROR_CODE optimizeAIModel( sl::AI_MODELS model, int gpu_id =0 ) ``` 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. ### function toString ```cpp * toString( const sl::SpatialMappingParameters::MAPPING_RESOLUTION & resolution ) ``` ### function operator<< ```cpp inline std::ostream & operator<<( std::ostream & os, const SpatialMappingParameters::MAPPING_RESOLUTION & resolution ) ``` ### function toString ```cpp String toString( const sl::SpatialMappingParameters::MAPPING_RANGE & range ) ``` ### function operator<< ```cpp inline std::ostream & operator<<( std::ostream & os, const SpatialMappingParameters::MAPPING_RANGE & range ) ``` ### function toString ```cpp String toString( const sl::SpatialMappingParameters::SPATIAL_MAP_TYPE & map_type ) ``` ### function fromString ```cpp bool fromString( const sl::String & map_type_str, sl::SpatialMappingParameters::SPATIAL_MAP_TYPE & map_type ) ``` ### function operator<< ```cpp inline std::ostream & operator<<( std::ostream & os, const SpatialMappingParameters::SPATIAL_MAP_TYPE & map_type ) ``` ### function DEFAULT_ID ```cpp const SensorID DEFAULT_ID( "00000000-0000-0000-0000-000000000000" ) ``` ### function defaultSensorDeviceIdentifier ```cpp SensorDeviceIdentifier defaultSensorDeviceIdentifier() ``` ### function operator<< ```cpp inline std::ostream & operator<<( std::ostream & os, const String & str ) ``` ### function saveJSONFile ```cpp bool saveJSONFile( const sl::String filepath, const sl::String & serialized_content, bool merge =false ) ``` ### function loadJSONFile ```cpp bool loadJSONFile( const sl::String filepath, sl::String & serialized_content ) ``` ### function toVerbose ```cpp String toVerbose( const ERROR_CODE & errorCode ) ``` Provide a concise sl::ERROR_CODE string. **Return**: A concise sl::ERROR_CODE string for the user. ### function isCameraOne ```cpp bool isCameraOne( const sl::MODEL ) ``` Check the type of a camera model. **Return**: true if the specified camera model is a monocular camera ### function generateVirtualStereoSerialNumber ```cpp unsigned int SL_CORE_EXPORT generateVirtualStereoSerialNumber( unsigned int serial_left, unsigned int serial_right ) ``` Generate a unique identifier for virtual stereo based on the serial numbers of the two ZED Ones. **Parameters**: * **serial_left** : Serial number of the left camera. * **serial_right** : 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). ### function str2unit ```cpp * str2unit( String unit ) ``` ### function toString ```cpp * toString( const AI_MODELS & model ) ``` ### function operator<< ```cpp inline ::std::ostream & operator<<( ::std::ostream & os, const AI_MODELS & model ) ``` ### function sleep_ms ```cpp inline void sleep_ms( int time ) ``` Blocks the execution of the current thread for **time** milliseconds. **Parameters**: * **time** : Number of milliseconds to wait. ### function sleep_us ```cpp inline void sleep_us( int time ) ``` Blocks the execution of the current thread for **time** microseconds. **Parameters**: * **time** : Number of microseconds to wait. ### function resetBenchmarkTimer ```cpp void resetBenchmarkTimer() ``` 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. ### function convertImage ```cpp ERROR_CODE SL_CORE_EXPORT convertImage( sl::Mat & image_in, sl::Mat & image_signed, cudaStream_t stream =0 ) ``` Convert Image format from Unsigned char to Signed char, designed for Unreal Engine pipeline, works on GPU memory. **Parameters**: * **image_in** : input image to convert * **image_signed** : output image to converted * **stream** : a cuda stream to put the compute to (def. 0) **Note**: If the Output Mat does not satisfies the requirements, it is freed and re-allocated. ### function blobFromImage ```cpp ERROR_CODE SL_CORE_EXPORT blobFromImage( sl::Mat & image_in, sl::Mat & tensor_out, sl::Resolution resolution_out, float scalefactor =1/255., sl::float3 mean =sl::float3(0, 0, 0), sl::float3 stddev =sl::float3(1, 1, 1), bool keep_aspect_ratio =true, bool swap_RB_channels =true, cudaStream_t stream =0 ) ``` Convert an image into a GPU Tensor in planar channel configuration (NCHW), ready to use for deep learning model. **Parameters**: * **image_in** : input image to convert * **tensor_out** : output GPU tensor * **resolution_out** : resolution of the output image, generally square, although not mandatory * **scalefactor** : Scale factor applied to each pixel value, typically to convert the char value into [0-1] float * **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) * **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) * **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 * **swap_RB_channels** : indicates if the Red and Blue channels should be swapped (RGB<->BGR or RGBA<->BGRA) * **stream** : a cuda stream to put the compute ### function blobFromImages ```cpp ERROR_CODE SL_CORE_EXPORT blobFromImages( std::vector< sl::Mat > & images_in, sl::Mat & tensor_out, sl::Resolution resolution_out, float scalefactor =1/255., sl::float3 mean =sl::float3(0, 0, 0), sl::float3 stddev =sl::float3(1, 1, 1), bool keep_aspect_ratio =true, bool swap_RB_channels =true, cudaStream_t stream =0 ) ``` Convert a list of images into a GPU Tensor in planar channel configuration (NCHW), ready to use for deep learning model. **Parameters**: * **images_in** : input images to convert * **tensor_out** : output GPU tensor batched * **resolution_out** : resolution of the output image, generally square, although not mandatory * **scalefactor** : Scale factor applied to each pixel value, typically to convert the char value into [0-1] float * **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) * **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) * **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 * **swap_RB_channels** : indicates if the Red and Blue channels should be swapped (RGB<->BGR or RGBA<->BGRA) * **stream** : a cuda stream to put the compute ### function computeRotationMatrixFromGravity ```cpp Rotation computeRotationMatrixFromGravity( sl::float3 axis_to_align, sl::float3 gravity_vector ) ``` Compute the rotation matrix from the gravity vector : the rotation can used to find the world rotation from the gravity of an IMU. **Parameters**: * **axis_to_align** : define the axis to align with the gravity, for instance : to align the "y" axis, axis_to_align = (0, 1, 0)' * **gravity_vector** : the gravity vector, acceleration set by an IMU **Return**: Rotation : rotation matrix, useful for Camera::detectFloorPlane as a gravity prior ### function getCoordinateTransformConversion3f ```cpp Matrix3f getCoordinateTransformConversion3f( COORDINATE_SYSTEM coord_system_src, COORDINATE_SYSTEM coord_system_dst ) ``` Get the coordinate transform conversion matrix to change coordinate system. **Parameters**: * **coord_system_src** : the source coordinate system. * **coord_system_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). ### function getCoordinateTransformConversion4f ```cpp Matrix4f getCoordinateTransformConversion4f( COORDINATE_SYSTEM coord_system_src, COORDINATE_SYSTEM coord_system_dst ) ``` Get the coordinate transform conversion matrix to change coordinate system. **Parameters**: * **coord_system_src** : the source coordinate system. * **coord_system_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). ### function convertCoordinateSystem ```cpp ERROR_CODE convertCoordinateSystem( Mat & floatMat, COORDINATE_SYSTEM coord_system_src, COORDINATE_SYSTEM coord_system_dst, MEM mem =MEM::BOTH, cudaStream_t stream =0 ) ``` Change the coordinate system of a matrix. **Parameters**: * **floatMat** : (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]. * **coord_system_src** : the current coordinate system of floatMat. * **coord_system_dst** : the destination coordinate system for floatMat. * **mem** : define which memory should be transformed from floatMat. If [MEM::BOTH] is specified, the function will automatically detect which memory is allocated and transform accordingly (GPU preferred if both are allocated). * **stream** : CUDA stream on which to perform the GPU transformation (only used when transforming GPU memory). **Return**: [ERROR_CODE::SUCCESS] if everything went well, [ERROR_CODE::FAILURE] otherwise. ### function convertCoordinateSystem ```cpp ERROR_CODE convertCoordinateSystem( Transform & motionMat, COORDINATE_SYSTEM coord_system_src, COORDINATE_SYSTEM coord_system_dst ) ``` Change the coordinate system of a transform matrix. **Parameters**: * **motionMat** : (in/out) matrix to transform * **coord_system_src** : the current coordinate system of motionMat. * **coord_system_dst** : the destination coordinate system for motionMat. **Return**: [ERROR_CODE::SUCCESS] if everything went well, [ERROR_CODE::FAILURE] otherwise. ### function applyTransform ```cpp ERROR_CODE applyTransform( Mat & floatMat, const Transform & transform, MEM mem =MEM::BOTH, cudaStream_t stream =0 ) ``` Apply a transformation (rotation and translation) to a point cloud matrix. **Parameters**: * **floatMat** : (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]. * **transform** : the transformation (rotation + translation) to apply to each point. * **mem** : define which memory should be transformed from floatMat. If [MEM::BOTH] is specified, the function will automatically detect which memory is allocated and transform accordingly (GPU preferred if both are allocated). * **stream** : CUDA stream on which to perform the GPU transformation (only used when transforming GPU memory). **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). ### function getUnitScale ```cpp float getUnitScale( UNIT unit_src, UNIT unit_dst ) ``` Get the unit factor to change units. **Parameters**: * **unit_src** : the source coordinate system. * **unit_dst** : the destination coordinate system. **Return**: float : unit scale (pt_coord_dst = factor * pt_coord_src). ### function convertUnit ```cpp ERROR_CODE convertUnit( Mat & floatMat, UNIT unit_src, UNIT unit_dst, MEM mem =MEM::BOTH, cudaStream_t stream =0 ) ``` Change the unit of a matrix. **Parameters**: * **floatMat** : (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]. * **unit_src** : the current unit of floatMat. * **unit_dst** : the destination unit for floatMat. * **mem** : define which memory should be transformed from floatMat. If [MEM::BOTH] is specified, the function will automatically detect which memory is allocated and transform accordingly (GPU preferred if both are allocated). * **stream** : CUDA stream on which to perform the GPU transformation (only used when transforming GPU memory). **Return**: [ERROR_CODE::SUCCESS] if everything went well, [ERROR_CODE::FAILURE] otherwise. ### function convertUnit ```cpp ERROR_CODE convertUnit( Transform & motionMat, UNIT unit_src, UNIT unit_dst ) ``` Change the unit (of the translations) of a transform matrix. **Parameters**: * **motionMat** : (in/out) matrix to transform * **unit_src** : the current unit of motionMat. * **unit_dst** : the destination unit for motionMat. **Return**: [ERROR_CODE::SUCCESS] if everything went well, [ERROR_CODE::FAILURE] otherwise. ### function getObjectClass ```cpp OBJECT_CLASS getObjectClass( OBJECT_SUBCLASS object_type ) ``` ### function getObjectSubClasses ```cpp std::vector< OBJECT_SUBCLASS > getObjectSubClasses( OBJECT_CLASS object_type ) ``` ### function getObjectSubClassAsCOCO ```cpp int getObjectSubClassAsCOCO( const OBJECT_SUBCLASS object_type ) ``` ### function generate_unique_id ```cpp String generate_unique_id() ``` Generate a UUID like unique id to help identify and track AI detections. ### function getIdx ```cpp inline int getIdx( BODY_18_PARTS part ) ``` Return associated index of each sl::BODY_18_PARTS. ### function getIdx ```cpp inline int getIdx( BODY_34_PARTS part ) ``` Return associated index of each sl::BODY_34_PARTS. ### function getIdx ```cpp inline int getIdx( BODY_38_PARTS part ) ``` Return associated index of each sl::BODY_38_PARTS. ### function toString ```cpp String toString( const sl::POSITION_TYPE & position_type ) ``` ### function operator<< ```cpp inline ::std::ostream & operator<<( ::std::ostream & os, const POSITION_TYPE & position_type ) ``` ### function toString ```cpp * toString( const MESH_FILE_FORMAT & mesh_frmt ) ``` ### function operator<< ```cpp inline std::ostream & operator<<( std::ostream & os, const MESH_FILE_FORMAT & mesh_frmt ) ``` ### function toString ```cpp * toString( const MESH_TEXTURE_FORMAT & text_frmt ) ``` ### function operator<< ```cpp inline std::ostream & operator<<( std::ostream & os, const MESH_TEXTURE_FORMAT & text_frmt ) ``` ### function toString ```cpp * toString( const sl::MeshFilterParameters::MESH_FILTER & mesh_filter ) ``` ### function operator<< ```cpp inline std::ostream & operator<<( std::ostream & os, const MeshFilterParameters::MESH_FILTER & mesh_filter ) ``` ### function toString ```cpp * toString( const PLANE_TYPE & type ) ``` ### function operator<< ```cpp inline std::ostream & operator<<( std::ostream & os, const PLANE_TYPE & type ) ``` ### function operator== ```cpp inline bool operator==( const CameraIdentifier & a, const CameraIdentifier & b ) ``` ### function operator!= ```cpp inline bool operator!=( const CameraIdentifier & a, const CameraIdentifier & b ) ``` ### function readFusionConfigurationFile ```cpp FusionConfiguration readFusionConfigurationFile( const std::string & json_config_filename, const int serial_number, const sl::COORDINATE_SYSTEM coord_sys, const sl::UNIT unit ) ``` Read a configuration JSON file to configure a fusion process. **Parameters**: * **json_config_filename** : The name of the JSON file containing the configuration. * **serial_number** : The serial number of the ZED Camera you want to retrieve. * **coord_sys** : The COORDINATE_SYSTEM in which you want the World Pose to be in. * **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. ### function readFusionConfigurationFile ```cpp std::vector< FusionConfiguration > readFusionConfigurationFile( const std::string & json_config_filename, const sl::COORDINATE_SYSTEM coord_sys, const sl::UNIT unit ) ``` Read a Configuration JSON file to configure a fusion process. **Parameters**: * **json_config_filename** : The name of the JSON file containing the configuration. * **coord_sys** : The COORDINATE_SYSTEM in which you want the World Pose to be in. * **unit** : The UNIT in which you want the World Pose to be in. **Return**: A vector of FusionConfiguration for all the camera present in the file. **Note**: Empty if no data were found for the requested camera. ### function readFusionConfiguration ```cpp std::vector< FusionConfiguration > readFusionConfiguration( const std::string & fusion_configuration, const sl::COORDINATE_SYSTEM coord_sys, const sl::UNIT unit ) ``` Read a Configuration JSON string to configure a fusion process. **Parameters**: * **fusion_configuration** : The string containing the configuration (it will be parsed as JSON). * **coord_sys** : Defines the COORDINATE_SYSTEM of the Fusion World Pose. * **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. ### function writeConfigurationFile ```cpp void writeConfigurationFile( const std::string & json_config_filename, std::vector< FusionConfiguration > & configuration, const sl::COORDINATE_SYSTEM coord_sys, const sl::UNIT unit ) ``` Write a Configuration JSON file to configure a fusion process. **Parameters**: * **json_config_filename** : The name of the JSON that will contain the information. * **configuration** A vector of FusionConfiguration listing all the camera configurations. * **coord_sys** : The COORDINATE_SYSTEM in which the World Pose is. * **unit** : The UNIT in which the World Pose is. ## Attributes Documentation ### variable TOO_FAR ```cpp static const float TOO_FAR = INFINITY; ``` Defines an unavailable depth value that is above the depth Max value. ### variable TOO_CLOSE ```cpp static const float TOO_CLOSE = -INFINITY; ``` Defines an unavailable depth value that is below the depth Min value. ### variable OCCLUSION_VALUE ```cpp static const float OCCLUSION_VALUE = NAN; ``` Defines an unavailable depth value that is on an occluded image area. ### variable INVALID_VALUE ```cpp static const float INVALID_VALUE = NAN; ``` ### variable STATIC_DEPTH ```cpp static const unsigned char STATIC_DEPTH = 255; ``` ### variable DYNAMIC_DEPTH ```cpp static const unsigned char DYNAMIC_DEPTH = 127; ``` ### variable VIDEO_SETTINGS_VALUE_AUTO ```cpp const int VIDEO_SETTINGS_VALUE_AUTO = -1; ``` ### variable BODY_18_BONES ```cpp const std::vector< std::pair< BODY_18_PARTS, BODY_18_PARTS > > BODY_18_BONES { {BODY_18_PARTS::NOSE, BODY_18_PARTS::NECK }, {BODY_18_PARTS::NECK, BODY_18_PARTS::RIGHT_SHOULDER}, {BODY_18_PARTS::RIGHT_SHOULDER, BODY_18_PARTS::RIGHT_ELBOW }, {BODY_18_PARTS::RIGHT_ELBOW, BODY_18_PARTS::RIGHT_WRIST }, {BODY_18_PARTS::NECK, BODY_18_PARTS::LEFT_SHOULDER }, {BODY_18_PARTS::LEFT_SHOULDER, BODY_18_PARTS::LEFT_ELBOW }, {BODY_18_PARTS::LEFT_ELBOW, BODY_18_PARTS::LEFT_WRIST }, {BODY_18_PARTS::RIGHT_SHOULDER, BODY_18_PARTS::RIGHT_HIP }, {BODY_18_PARTS::RIGHT_HIP, BODY_18_PARTS::RIGHT_KNEE }, {BODY_18_PARTS::RIGHT_KNEE, BODY_18_PARTS::RIGHT_ANKLE }, {BODY_18_PARTS::LEFT_SHOULDER, BODY_18_PARTS::LEFT_HIP }, {BODY_18_PARTS::LEFT_HIP, BODY_18_PARTS::LEFT_KNEE }, {BODY_18_PARTS::LEFT_KNEE, BODY_18_PARTS::LEFT_ANKLE }, {BODY_18_PARTS::RIGHT_SHOULDER, BODY_18_PARTS::LEFT_SHOULDER }, {BODY_18_PARTS::RIGHT_HIP, BODY_18_PARTS::LEFT_HIP }, {BODY_18_PARTS::NOSE, BODY_18_PARTS::RIGHT_EYE }, {BODY_18_PARTS::RIGHT_EYE, BODY_18_PARTS::RIGHT_EAR }, {BODY_18_PARTS::NOSE, BODY_18_PARTS::LEFT_EYE }, {BODY_18_PARTS::LEFT_EYE, BODY_18_PARTS::LEFT_EAR } }; ``` Lists links of human body keypoints for sl::BODY_FORMAT::BODY_18. Useful for display. ### variable BODY_34_BONES ```cpp const std::vector< std::pair< BODY_34_PARTS, BODY_34_PARTS > > BODY_34_BONES; ``` Lists links of human body keypoints for sl::BODY_FORMAT::BODY_34. Useful for display. ### variable BODY_38_BONES ```cpp const std::vector< std::pair< BODY_38_PARTS, BODY_38_PARTS > > BODY_38_BONES; ``` Lists links of human body keypoints for sl::BODY_FORMAT::BODY_38. Useful for display. --- # sl::CameraParameters **Module:** **Depth Sensing Module** Structure containing the intrinsic parameters of a camera. More... `#include ` ## Detailed Description ```cpp struct sl::CameraParameters; ``` Structure containing the intrinsic parameters of a camera. **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). * Those parameters given after sl::Camera.open() call, represent the camera matrix corresponding to rectified or unrectified images. * 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. * Since distortion is corrected during rectification, distortion should not be considered on rectified images. That information about the camera will be returned by sl::Camera.getCameraInformation(). ## Public Functions Documentation ### function scale ```cpp inline CameraParameters scale( sl::Resolution const & output_resolution ) const ``` Return the sl::CameraParameters for another resolution. **Parameters**: * **output_resolution** : Resolution in which to get the new sl::CameraParameters. **Return**: The sl::CameraParameters for the resolution given as input. ## Public Attributes Documentation ### variable fx ```cpp float fx = 0.f; ``` Focal length in pixels along x axis. ### variable fy ```cpp float fy = 0.f; ``` Focal length in pixels along y axis. ### variable cx ```cpp float cx = 0.f; ``` Optical center along x axis, defined in pixels (usually close to width / 2). ### variable cy ```cpp float cy = 0.f; ``` Optical center along y axis, defined in pixels (usually close to height / 2). ### variable disto ```cpp double[12] disto = {0.}; ``` 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. ### variable v_fov ```cpp float v_fov = 0.f; ``` Vertical field of view, in degrees. ### variable h_fov ```cpp float h_fov = 0.f; ``` Horizontal field of view, in degrees. ### variable d_fov ```cpp float d_fov = 0.f; ``` Diagonal field of view, in degrees. ### variable image_size ```cpp Resolution image_size = Resolution(0, 0); ``` Size in pixels of the images given by the camera. ### variable focal_length_metric ```cpp float focal_length_metric = 0.f; ``` Real focal length in millimeters. --- # sl::CalibrationParameters **Module:** **Depth Sensing Module** Structure containing intrinsic and extrinsic parameters of the camera (translation and rotation). More... `#include ` ## Detailed Description ```cpp struct sl::CalibrationParameters; ``` Structure containing intrinsic and extrinsic parameters of the camera (translation and rotation). **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. * Those values may be adjusted or not by the self-calibration to get a proper image alignment. * 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. * It means that images after rectification process (given by sl::Camera.retrieveImage()) 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. That information about the camera will be returned by sl::Camera.getCameraInformation(). ## Public Functions Documentation ### function getCameraBaseline ```cpp float getCameraBaseline() const ``` Return the baseline of the camera in the sl::UNIT defined in sl::InitParameters.coordinate_units. ### function scale ```cpp inline CalibrationParameters scale( sl::Resolution const & output_resolution ) const ``` computes and returns the calibration associated to the query resolution **Parameters**: * **output_resolution** the query resolution **Return**: CalibrationParameters ## Public Attributes Documentation ### variable left_cam ```cpp CameraParameters left_cam; ``` Intrinsics sl::CameraParameters of the left camera. ### variable right_cam ```cpp CameraParameters right_cam; ``` Intrinsics sl::CameraParameters of the right camera. ### variable stereo_transform ```cpp Transform stereo_transform; ``` Left to right camera transform, expressed in user coordinate system and unit (defined by InitParameters). --- # sl::Pose **Module:** **Positional Tracking Module** Class containing positional tracking data giving the position and orientation of the camera in 3D space. More... `#include ` ## Detailed Description ```cpp class sl::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. ## Public Functions Documentation ### function Pose ```cpp Pose() ``` Default constructor. Creates an empty sl::Pose (identity). ### function Pose ```cpp Pose( const Pose & pose ) ``` Copy constructor (deep copy). ### function Pose ```cpp Pose( const Transform & pose_data, unsigned long long timestamp =0, int confidence =0 ) ``` Constructor. Initializes the transform of the sl::Pose with a sl::Transform (deep copy). ### function ~Pose ```cpp ~Pose() ``` Default destructor. ### function getTranslation ```cpp Translation getTranslation() const ``` Returns the sl::Translation corresponding to the current sl::Pose. **Return**: sl::Translation created from the sl::Pose values. ### function getOrientation ```cpp Orientation getOrientation() const ``` Returns the sl::Orientation corresponding to the current sl::Pose. **Return**: sl::Orientation created from the sl::Pose values. ### function getRotationMatrix ```cpp Rotation getRotationMatrix() const ``` Returns the sl::Rotation corresponding to the current sl::Pose. **Return**: sl::Rotation created from the sl::Pose values. ### function getRotationVector ```cpp float3 getRotationVector() const ``` Returns the 3x1 rotation vector (obtained from 3x3 rotation matrix using Rodrigues formula) corresponding to the current sl::Pose. **Return**: Rotation vector created from the sl::Pose values. ### function getEulerAngles ```cpp float3 getEulerAngles( bool radian =true ) const ``` Converts the rotation component of the sl::Pose into Euler angles. **Parameters**: * **radian** : Whether the angle will be returned in radian or degree. **Return**: Euler angles created from the sl::Pose values as a sl::float3 representing the rotations around the X, Y and Z axes using YZX convention. ## Public Attributes Documentation ### variable pose_data ```cpp Transform pose_data; ``` sl::Transform containing the rotation and translation data of the sl::Pose. ### variable timestamp ```cpp sl::Timestamp timestamp; ``` sl::Timestamp of the sl::Pose. This timestamp should be compared with the camera timestamp for synchronization. ### variable pose_confidence ```cpp int pose_confidence; ``` 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 ### variable pose_covariance ```cpp float[36] pose_covariance; ``` 6x6 pose covariance matrix of translation (the first 3 values) and rotation in so3 (the last 3 values). ### variable valid ```cpp bool valid; ``` Whether the tracking is activated or not. **Note**: You should check that first if something is wrong. ### variable twist ```cpp float[6] twist; ``` Twist of the camera available in reference camera. This expresses velocity in free space, broken into its linear and angular parts. ### variable twist_covariance ```cpp float[36] twist_covariance; ``` Row-major representation of the 6x6 twist covariance matrix of the camera. This expresses the uncertainty of the twist. --- # sl::SensorsData **Module:** **Core Module** Structure containing all sensors data (except image sensors) to be used for positional tracking or environment study. More... `#include ` ## Public Classes | | Name | | -------------- | -------------- | | struct | **BarometerData**
Structure containing data from the barometer sensor. | | struct | **IMUData**
Structure containing data from the IMU sensor. | | struct | **MagnetometerData**
Structure containing data from the magnetometer sensor. | | struct | **TemperatureData**
Structure containing data from the temperature sensors. | ## Detailed Description ```cpp struct sl::SensorsData; ``` Structure 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. * They are specified by a note "Not available in SVO or STREAM mode." in the documentation of a specific data. * If nothing is mentioned in the documentation, they are available in all input modes. ## Public Types Documentation ### enum CAMERA_MOTION_STATE | Enumerator | Value | Description | | ---------- | ----- | ----------- | | STATIC | | The camera is static. | | MOVING | | The camera is moving. | | FALLING | | The camera is falling. | Lists different states of the camera motion. ## Public Functions Documentation ### function SensorsData ```cpp SensorsData() ``` Default constructor. Creates an empty sl::SensorsData (identity). ### function SensorsData ```cpp SensorsData( const SensorsData & data ) ``` Copy constructor (deep copy). ## Public Attributes Documentation ### variable barometer ```cpp BarometerData barometer; ``` Barometer data. ### variable temperature ```cpp TemperatureData temperature; ``` Temperature data. ### variable magnetometer ```cpp MagnetometerData magnetometer; ``` Magnetometer data. ### variable imu ```cpp IMUData imu; ``` IMU data. ### variable camera_moving_state ```cpp CAMERA_MOTION_STATE camera_moving_state; ``` Motion state of the camera. ### variable image_sync_trigger ```cpp int image_sync_trigger; ``` Indicates if the sensors data has been taken during a frame capture on sensor. If the value is 1, the data has been taken during the same time than a frame has been acquired by the left sensor (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. --- # sl::PositionalTrackingParameters **Module:** **Positional Tracking Module** Structure containing a set of parameters for the positional tracking module initialization. More... `#include ` ## Detailed Description ```cpp class sl::PositionalTrackingParameters; ``` Structure containing a set of parameters for the positional tracking module initialization. **Note**: Parameters can be adjusted by the user. ## Public Functions Documentation ### function PositionalTrackingParameters ```cpp PositionalTrackingParameters( Transform init_position_ =Transform(), bool enable_memory_ =true, bool enable_pose_smoothing_ =false, String area_path_ =String(), bool set_floor_as_origin_ =false, bool enable_imu_fusion_ =true, bool set_as_static_ =false, float depth_min_range =-1.f, bool set_gravity_as_origin_ =true, POSITIONAL_TRACKING_MODE mode =POSITIONAL_TRACKING_MODE::GEN_3, bool enable_localization_only =false, bool enable_2d_ground_mode =false ) ``` Default constructor. Sets all parameters to their default and optimized values. ## Public Attributes Documentation ### variable initial_world_transform ```cpp Transform initial_world_transform; ``` Position of the camera in the world frame when the camera is started. **Note**: The camera frame (which defines the reference frame for the camera) is by default positioned at the world frame when tracking is started. Use this sl::Transform to place the camera frame in the world frame. Default: Identity matrix. ### variable enable_area_memory ```cpp bool enable_area_memory; ``` Whether the camera can remember its surroundings. **Warning**: * This mode requires more resources to run, but greatly improves tracking accuracy. * We recommend leaving it on by default. This helps correct positional tracking drift and can be helpful for positioning different cameras relative to one other in space. Default: true ### variable enable_pose_smoothing ```cpp bool enable_pose_smoothing; ``` Whether to enable smooth pose correction for small drift correction. Default: false ### variable set_floor_as_origin ```cpp bool set_floor_as_origin; ``` Initializes the tracking to be aligned with the floor plane to better position the camera in space. **Note**: * This launches floor plane detection in the background until a suitable floor plane is found. * 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. * The camera needs to look at the floor during initialization for optimum results. Default: false ### variable area_file_path ```cpp String area_file_path; ``` Path of an area localization file that describes the surroundings (saved from a previous tracking session). **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. * The '.area' file can only be used with the same depth mode (sl::DEPTH_MODE) as the one used during area recording. Default: (empty) ### variable enable_imu_fusion ```cpp bool enable_imu_fusion; ``` Whether to enable the IMU fusion. **Note**: * This setting has no impact on the tracking of a camera. * sl::MODEL::ZED does not have an IMU. When set to false, only the optical odometry will be used. Default: true ### variable set_as_static ```cpp bool set_as_static; ``` 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::getPosition() will return the value set as initial_world_transform. Default: false ### variable depth_min_range ```cpp float depth_min_range; ``` 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) ### variable set_gravity_as_origin ```cpp bool set_gravity_as_origin; ``` Whether to override 2 of the 3 rotations from initial_world_transform using the IMU gravity. **Note**: This parameter does nothing on sl::ZED::MODEL since it does not have an IMU. Default: true ### variable mode ```cpp POSITIONAL_TRACKING_MODE mode; ``` 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 ### variable enable_localization_only ```cpp bool enable_localization_only = false; ``` Whether to enable the area mode in localize only mode. ### variable enable_2d_ground_mode ```cpp bool enable_2d_ground_mode = false; ``` Whether to enable the 2D ground mode. --- # sl::RecordingParameters **Module:** **Video Module** Structure containing the options used to record. More... `#include ` ## Detailed Description ```cpp struct sl::RecordingParameters; ``` Structure containing the options used to record. **Note**: Parameters can be adjusted by the user. The default constructor sets all parameters to their default settings. ## Public Functions Documentation ### function RecordingParameters ```cpp RecordingParameters( String video_filename_ ="myRecording.svo2", SVO_COMPRESSION_MODE compression_mode_ =SVO_COMPRESSION_MODE::H265, unsigned int target_framerate_ =0, unsigned int bitrate_ =0, bool transcode_streaming_input_ =false, String encryption_key_ =String(), SVO_ENCODING_PRESET encoding_preset_ =SVO_ENCODING_PRESET::DEFAULT ) ``` Default constructor. All the parameters are set to their default values. ## Public Attributes Documentation ### variable video_filename ```cpp String video_filename; ``` Filename of the file to save the recording into. ### variable compression_mode ```cpp SVO_COMPRESSION_MODE compression_mode = SVO_COMPRESSION_MODE::H265; ``` Compression mode the recording. Default: sl::SVO_COMPRESSION_MODE::H265 ### variable bitrate ```cpp unsigned int bitrate = 0; ``` Overrides the default bitrate of the SVO file, in kbits/s. **Note**: * Only works if compression_mode is H264 or H265. * Available range: 0 or [1000 - 60000] Default: 0 (the default values associated with the resolution) ### variable target_framerate ```cpp unsigned int target_framerate = 0; ``` Framerate for the recording file. **Warning**: * This framerate must be below or equal to the camera framerate and camera framerate must be a multiple of the target framerate. * It means that it must respect ` camera_frameratetarget_framerate == 0`. * Allowed framerates are 15,30, 60 or 100 if possible. * Any other values will be discarded and camera FPS will be taken. Default: 0 (camera framerate will be taken) ### variable transcode_streaming_input ```cpp bool transcode_streaming_input = false; ``` Defines whether to decode and re-encode a streaming source. **Note**: * If set to false, it will avoid decoding/re-encoding and convert directly streaming input into a SVO file. * This saves a encoding session and can be especially useful on NVIDIA Geforce cards where the number of encoding session is limited. * compression_mode, target_framerate and bitrate will be ignored in this mode. Default: false ### variable encryption_key ```cpp String encryption_key; ``` Optional encryption key or passphrase to protect the SVO file. **Note**: * Requires OpenSSL (libcrypto) to be available on the system at runtime. * This feature uses hardware-accelerated AES on both x86 (AES-NI) and ARM (ARMv8 Crypto Extensions) via OpenSSL. When set, the SVO file is AES-256-CTR encrypted on the fly during recording. The same value must be provided in sl::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) ### variable encoding_preset ```cpp SVO_ENCODING_PRESET encoding_preset = SVO_ENCODING_PRESET::DEFAULT; ``` Encoding preset for the hardware encoder. **Note**: Only applicable when compression_mode is H264 or H265 (lossy or lossless). Controls the speed/quality tradeoff of the GPU encoder. Default: sl::SVO_ENCODING_PRESET::DEFAULT --- # sl::StreamingParameters **Module:** **Video Module** Structure containing the options used to stream with the ZED SDK. More... `#include ` ## Detailed Description ```cpp struct sl::StreamingParameters; ``` Structure containing the options used to stream with the ZED SDK. **Note**: Parameters can be adjusted by the user. The default constructor sets all parameters to their default settings. ## Public Functions Documentation ### function StreamingParameters ```cpp StreamingParameters( STREAMING_CODEC codec_ =STREAMING_CODEC::H265, unsigned short port_ =30000, unsigned int bitrate_ =0, int gop_size_ =-1, bool adaptative_bitrate_ =false, unsigned short chunk_size_ =16084, unsigned int target_framerate_ =0 ) ``` Default constructor. All the parameters are set to their default values. ## Public Attributes Documentation ### variable codec ```cpp STREAMING_CODEC codec = STREAMING_CODEC::H265; ``` Encoding used for streaming. ### variable port ```cpp unsigned short port = 30000; ``` Port used for streaming. **Warning**: * Port must be an even number. Any odd number will be rejected. * Port must be opened. ### variable bitrate ```cpp unsigned int bitrate = 0; ``` Streaming bitrate (in Kbits/s) used for streaming. **Note**: Available range: [1000 - 60000] | sl::STREAMING_CODEC | sl::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) ### variable gop_size ```cpp int gop_size = -1; ``` GOP size in number of frames. **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. * Maximum value: 256 Default: -1 (the GOP size will last at maximum 2 seconds, depending on camera FPS) ### variable adaptative_bitrate ```cpp bool adaptative_bitrate = false; ``` Defines whether the adaptive bitrate is enable. **Note**: * Bitrate will be adjusted depending the number of packet dropped during streaming. * 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). Default: false ### variable chunk_size ```cpp unsigned short chunk_size = 16084; ``` Size of a single chunk. **Note**: * Stream buffers are divided into X number of chunks where each chunk is chunk_size bytes long. * 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. * Increasing this value can decrease latency. * Available range: [1024 - 65000] Default: 16084 ### variable target_framerate ```cpp unsigned int target_framerate = 0; ``` Framerate for the streaming output. **Warning**: * This framerate must be below or equal to the camera framerate. * Allowed framerates are 15, 30, 60 or 100 if possible. * Any other values will be discarded and camera FPS will be taken. Default: 0 (camera framerate will be taken) --- # sl::ObjectDetectionParameters **Module:** **Object Detection Module** Structure containing a set of parameters for the object detection module. More... `#include ` ## Detailed Description ```cpp class sl::ObjectDetectionParameters; ``` Structure containing a set of parameters for the object detection module. **Note**: Parameters can be adjusted by the user. The default constructor sets all parameters to their default settings. ## Public Functions Documentation ### function ObjectDetectionParameters ```cpp ObjectDetectionParameters( bool enable_tracking_ =true, bool enable_segmentation_ =false, OBJECT_DETECTION_MODEL detection_model =OBJECT_DETECTION_MODEL::MULTI_CLASS_BOX_FAST, float max_range_ =-1.f, BatchParameters batch_trajectories_parameters =BatchParameters(), OBJECT_FILTERING_MODE filtering_mode_ =OBJECT_FILTERING_MODE::NMS3D, float prediction_timeout_s =0.2f, bool allow_reduced_precision_inference =false, unsigned int instance_id =0, const sl::String & fused_objects_group_name ="", const sl::String & custom_onnx_file ="", const sl::Resolution & custom_onnx_dynamic_input_shape =sl::Resolution(512, 512) ) ``` Default constructor. All the parameters are set to their default values. ## Public Attributes Documentation ### variable instance_module_id ```cpp unsigned int instance_module_id = 0; ``` Id of the module instance. This is used to identify which object detection module instance is used. ### variable enable_tracking ```cpp bool enable_tracking = true; ``` Whether the object detection system includes object tracking capabilities across a sequence of images. ### variable enable_segmentation ```cpp bool enable_segmentation = false; ``` Whether the object masks will be computed. ### variable detection_model ```cpp OBJECT_DETECTION_MODEL detection_model = OBJECT_DETECTION_MODEL::MULTI_CLASS_BOX_FAST; ``` sl::OBJECT_DETECTION_MODEL to use. ### variable fused_objects_group_name ```cpp sl::String fused_objects_group_name; ``` In a multi camera setup, specify which group this model belongs to. **Note**: This parameter is not used when not using a multi-camera setup and must be set in a multi camera setup. 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. ### variable custom_onnx_file ```cpp sl::String custom_onnx_file; ``` Path to the YOLO-like onnx file for custom object detection ran in the ZED SDK. **Note**: This parameter is useless when detection_model is not [OBJECT_DETECTION_MODEL::CUSTOM_YOLOLIKE_BOX_OBJECTS]. **Attention**: * - The model must be a YOLO-like model. * - The caching uses the deserialized `custom_onnx_file` along with your GPU specs to decide whether to use the cached optimized model or to optimize the passed onnx model. If you change the weights of the onnx file and pass the same path, the ZED SDK will detect the difference and optimize the new model. 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. ### variable custom_onnx_dynamic_input_shape ```cpp sl::Resolution custom_onnx_dynamic_input_shape; ``` 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) ### variable max_range ```cpp float max_range = -1.f; ``` Upper depth range for detections. **Note**: The value cannot be greater than sl::InitParameters.depth_maximum_distance and its unit is defined in sl::InitParameters.coordinate_units. Default: -1.f (value set in sl::InitParameters.depth_maximum_distance) ### variable batch_parameters ```cpp BatchParameters batch_parameters; ``` 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). ### variable filtering_mode ```cpp OBJECT_FILTERING_MODE filtering_mode = OBJECT_FILTERING_MODE::NMS3D; ``` Filtering mode that should be applied to raw detections. **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. * For custom object, it is recommended to use sl::OBJECT_FILTERING_MODE::NMS_3D_PER_CLASS or sl::OBJECT_FILTERING_MODE::NONE. * In this case, you might need to add your own NMS filter before ingesting the boxes into the object detection module. Default: sl::OBJECT_FILTERING_MODE::NMS_3D (same behavior as previous ZED SDK version) ### variable prediction_timeout_s ```cpp float prediction_timeout_s; ``` Prediction duration of the ZED SDK when an object is not detected anymore before switching its state to sl::OBJECT_TRACKING_STATE::SEARCHING. **Note**: * During this time, the object will have sl::OBJECT_TRACKING_STATE::OK state even if it is not detected. * The duration is expressed in seconds. **Warning**: * prediction_timeout_s will be clamped to 1 second as the prediction is getting worse with time. * Setting this parameter to 0 disables the ZED SDK predictions. It prevents the jittering of the object state when there is a short misdetection. The user can define their own prediction time duration. ### variable allow_reduced_precision_inference ```cpp bool allow_reduced_precision_inference; ``` Whether to allow inference to run at a lower precision to improve runtime and memory usage. **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. * 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. * The accuracy loss should not exceed 1-2% on the compatible models. * The current compatible models are all sl::AI_MODELS::HUMAN_BODY_XXXX. It might increase the initial optimization time and could include downloading calibration data or calibration cache and slightly reduce the accuracy. --- # sl::BodyTrackingParameters **Module:** **Body Tracking Module** Structure containing a set of parameters for the body tracking module. More... `#include ` ## Detailed Description ```cpp struct sl::BodyTrackingParameters; ``` Structure containing a set of parameters for the body tracking module. **Note**: Parameters can be adjusted by the user. The default constructor sets all parameters to their default settings. ## Public Functions Documentation ### function BodyTrackingParameters ```cpp BodyTrackingParameters( bool enable_tracking_ =true, bool enable_segmentation_ =false, BODY_TRACKING_MODEL detection_model =BODY_TRACKING_MODEL::HUMAN_BODY_ACCURATE, bool enable_body_fitting_ =false, float max_range_ =-1.f, BODY_FORMAT body_format_ =BODY_FORMAT::BODY_18, BODY_KEYPOINTS_SELECTION body_selection =BODY_KEYPOINTS_SELECTION::FULL, float prediction_timeout_s =0.2f, bool allow_reduced_precision_inference =false, unsigned int instance_id =0 ) ``` Default constructor. All the parameters are set to their default values. ## Public Attributes Documentation ### variable instance_module_id ```cpp unsigned int instance_module_id = 0; ``` Id of the module instance. This is used to identify which body tracking module instance is used. ### variable enable_tracking ```cpp bool enable_tracking = true; ``` Whether the body tracking system includes body/person tracking capabilities across a sequence of images. ### variable enable_segmentation ```cpp bool enable_segmentation = false; ``` Whether the body/person masks will be computed. ### variable detection_model ```cpp BODY_TRACKING_MODEL detection_model = BODY_TRACKING_MODEL::HUMAN_BODY_ACCURATE; ``` sl::BODY_TRACKING_MODEL to use. ### variable enable_body_fitting ```cpp bool enable_body_fitting = false; ``` Whether to apply the body fitting. ### variable body_format ```cpp BODY_FORMAT body_format = BODY_FORMAT::BODY_18; ``` Body format to be outputted by the ZED SDK with sl::Camera.retrieveBodies(). ### variable body_selection ```cpp BODY_KEYPOINTS_SELECTION body_selection = BODY_KEYPOINTS_SELECTION::FULL; ``` Selection of keypoints to outputted by the ZED SDK with sl::Camera.retrieveBodies(). ### variable max_range ```cpp float max_range = -1.f; ``` Upper depth range for detections. **Note**: The value cannot be greater than sl::InitParameters.depth_maximum_distance and its unit is defined in sl::InitParameters.coordinate_units. Default: -1.f (value set in sl::InitParameters.depth_maximum_distance) ### variable prediction_timeout_s ```cpp float prediction_timeout_s; ``` Prediction duration of the ZED SDK when an object is not detected anymore before switching its state to sl::OBJECT_TRACKING_STATE::SEARCHING. **Note**: * During this time, the object will have sl::OBJECT_TRACKING_STATE::OK state even if it is not detected. * The duration is expressed in seconds. **Warning**: * prediction_timeout_s will be clamped to 1 second as the prediction is getting worse with time. * Setting this parameter to 0 disables the ZED SDK predictions. It prevents the jittering of the object state when there is a short misdetection. The user can define their own prediction time duration. ### variable allow_reduced_precision_inference ```cpp bool allow_reduced_precision_inference; ``` Whether to allow inference to run at a lower precision to improve runtime and memory usage. **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. * 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. * The accuracy loss should not exceed 1-2% on the compatible models. * The current compatible models are all sl::AI_MODELS::HUMAN_BODY_XXXX. It might increase the initial optimization time and could include downloading calibration data or calibration cache and slightly reduce the accuracy. --- # sl::Bodies **Module:** **Body Tracking Module** Class containing the results of the body tracking module. More... `#include ` ## Detailed Description ```cpp class sl::Bodies; ``` Class containing the results of the body tracking module. The detected bodies/persons are listed in body_list. ## Public Functions Documentation ### function getBodyDataFromId ```cpp bool getBodyDataFromId( sl::BodyData & bodyData, int bodyDataId ) ``` Method that looks for a given body id in the current bodies list. **Parameters**: * **bodyData** : sl::BodyData to fill if the search succeeded. * **bodyDataId** : Id of the sl::BodyData to search. **Return**: True if found, otherwise false. ## Public Attributes Documentation ### variable timestamp ```cpp sl::Timestamp timestamp; ``` Timestamp corresponding to the frame acquisition. This value is especially useful for the async mode to synchronize the data. ### variable body_list ```cpp std::vector< sl::BodyData > body_list; ``` Vector of detected bodies/persons. ### variable is_new ```cpp bool is_new = false; ``` Whether body_list has already been retrieved or not. ### variable is_tracked ```cpp bool is_tracked = false; ``` Whether both the body tracking and the world orientation has been setup. ### variable inference_precision_mode ```cpp sl::INFERENCE_PRECISION inference_precision_mode; ``` 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. ### variable body_format ```cpp BODY_FORMAT body_format; ``` Body format used in sl::BodyTrackingParameters.body_format parameter. --- # sl::BodiesBatch **Module:** **Body Tracking Module** Class containing batched data of a detected bodies/persons from the body tracking module. `#include ` ## Public Attributes Documentation ### variable id ```cpp int id; ``` Id of the batch. ### variable tracking_state ```cpp OBJECT_TRACKING_STATE tracking_state; ``` Bodies/persons tracking state. ### variable positions ```cpp std::vector< sl::float3 > positions; ``` Vector of positions for each body/person. ### variable position_covariances ```cpp std::vector< std::array< float, 6 > > position_covariances; ``` Vector of positions' covariances for each body/person. ### variable velocities ```cpp std::vector< sl::float3 > velocities; ``` Vector of 3D velocities for each body/person. ### variable timestamps ```cpp std::vector< sl::Timestamp > timestamps; ``` Vector of timestamps for each body/person. ### variable bounding_boxes ```cpp std::vector< std::vector< sl::float3 > > bounding_boxes; ``` Vector 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. ```cpp 1 ------ 2 / /| 0 ------ 3 | | Object | 6 | |/ 4 ------ 7 ``` ### variable bounding_boxes_2d ```cpp std::vector< std::vector< sl::uint2 > > bounding_boxes_2d; ``` Vector of 2D bounding boxes for each body/person. **Note**: Expressed in pixels on the original image resolution, `[0, 0]` is the top left corner. ```cpp A ------ B | Object | D ------ C ``` ### variable confidences ```cpp std::vector< float > confidences; ``` Vector of confidences for each body/person. ### variable action_states ```cpp std::vector< OBJECT_ACTION_STATE > action_states; ``` Vector of action states for each body/person. ### variable keypoints_2d ```cpp std::vector< std::vector< sl::float2 > > keypoints_2d; ``` Vector 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. ### variable keypoints ```cpp std::vector< std::vector< sl::float3 > > keypoints; ``` Vector 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. ### variable head_bounding_boxes_2d ```cpp std::vector< std::vector< sl::uint2 > > head_bounding_boxes_2d; ``` Vector 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. ### variable head_bounding_boxes ```cpp std::vector< std::vector< sl::float3 > > head_bounding_boxes; ``` Vector 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. ### variable head_positions ```cpp std::vector< sl::float3 > head_positions; ``` Vector 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. ### variable keypoint_confidences ```cpp std::vector< std::vector< float > > keypoint_confidences; ``` Vector of detection confidences vector 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. --- # sl::BodyData **Module:** **Body Tracking Module** Class containing data of a detected body/person such as its bounding_box, id and its 3D position. `#include ` ## Public Functions Documentation ### function BodyData ```cpp BodyData() ``` Default constructor. ### function ~BodyData ```cpp ~BodyData() ``` Default destructor. ## Public Attributes Documentation ### variable id ```cpp int id; ``` Body/person identification number. **Note**: * Only available if sl::BodyTrackingParameters.enable_tracking is activated. * Otherwise, it will be set to -1. It is used as a reference when tracking the body through the frames. ### variable unique_object_id ```cpp String unique_object_id; ``` Unique id to help identify and track AI detections. It can be either generated externally, or by using generate_unique_id() or left empty. ### variable tracking_state ```cpp OBJECT_TRACKING_STATE tracking_state; ``` Body/person tracking state. ### variable action_state ```cpp OBJECT_ACTION_STATE action_state; ``` Body/person action state. ### variable position ```cpp sl::float3 position; ``` Body/person 3D centroid. **Note**: It is defined in sl::InitParameters.coordinate_units and expressed in sl::RuntimeParameters.measure3D_reference_frame. ### variable velocity ```cpp sl::float3 velocity; ``` Body/person 3D velocity. **Note**: It is defined in `sl::InitParameters.coordinate_units / s` and expressed in sl::RuntimeParameters.measure3D_reference_frame. ### variable position_covariance ```cpp float[6] position_covariance; ``` Covariance matrix of the 3D position. **Note**: It is represented by its upper triangular matrix value ```cpp = [p0, p1, p2] [p1, p3, p4] [p2, p4, p5] ``` where pi is `position_covariance[i]` ### variable bounding_box_2d ```cpp std::vector< sl::uint2 > bounding_box_2d; ``` 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. ```cpp A ------ B | Object | D ------ C ``` ### variable mask ```cpp sl::Mat mask; ``` 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]](OBJECT_TRACKING_STATE)) that have a valid depth. * Otherwise, the mask will not be initialized (`mask.isInit() == false`). ### variable confidence ```cpp float confidence; ``` Detection confidence value of the body/person. From 0 to 100, a low value means the body might not be localized perfectly. ### variable bounding_box ```cpp std::vector< sl::float3 > bounding_box; ``` 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. ```cpp 1 ------ 2 / /| 0 ------ 3 | | Object | 6 | |/ 4 ------ 7 ``` ### variable dimensions ```cpp sl::float3 dimensions; ``` 3D body/person dimensions: width, height, length. **Note**: It is defined in sl::InitParameters.coordinate_units and expressed in sl::RuntimeParameters.measure3D_reference_frame. ### variable keypoint_2d ```cpp std::vector< sl::float2 > keypoint_2d; ``` 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. ### variable keypoint ```cpp std::vector< sl::float3 > keypoint; ``` 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. ### variable head_bounding_box_2d ```cpp std::vector< sl::uint2 > head_bounding_box_2d; ``` 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. ### variable head_bounding_box ```cpp std::vector< sl::float3 > head_bounding_box; ``` 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. ### variable head_position ```cpp sl::float3 head_position; ``` 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. ### variable keypoint_confidence ```cpp std::vector< float > keypoint_confidence; ``` Vector 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. ### variable keypoint_covariances ```cpp std::vector< std::array< float, 6 > > keypoint_covariances; ``` Vector 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. ### variable local_position_per_joint ```cpp std::vector< sl::float3 > local_position_per_joint; ``` Vector 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]. ### variable local_orientation_per_joint ```cpp std::vector< sl::float4 > local_orientation_per_joint; ``` Vector of local orientation for each keypoint. **Note**: The orientation is represented by a quaternion stored in a sl::float4 (`sl::float4 q = sl::float4(qx, qy, qz, qw);`) **Warning**: Not available with [sl::BODY_FORMAT::BODY_18]. ### variable global_root_orientation ```cpp sl::float4 global_root_orientation; ``` Global root orientation of the skeleton. **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]. The orientation is also represented by a quaternion with the same format as local_orientation_per_joint. --- # sl::CameraIdentifier **Module:** **Fusion Module** Used to identify a specific camera in the Fusion API. `#include ` ## Public Functions Documentation ### function CameraIdentifier ```cpp inline CameraIdentifier() ``` ### function CameraIdentifier ```cpp inline CameraIdentifier( uint64_t sn_ ) ``` ### function get ```cpp inline sl::String get() const ``` ### function save ```cpp bool save( const String & filename ) const ``` Saves the current set of parameters into a file to be reloaded with the load() method. **Parameters**: * **filename** : Name of the file which will be created to store the parameters (extension '.json' 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. * In case a file already exists, the method will return false and existing file will not be updated. ### function load ```cpp bool load( const String & filename ) ``` Loads a set of parameters from the values contained in a previously saved file. **Parameters**: * **filename** : Path to the file from which the parameters will be loaded (extension '.json' will be added at the end of the filename if not detected). **Return**: True if the file was successfully loaded, otherwise false. ### function encode ```cpp bool encode( String & serialized_content ) const ``` Generate a JSON Object (with the struct type as a key) containing the serialized struct, converted into a string. **Parameters**: * **serialized_content** output string containing the JSON Object **Return**: True if file was successfully saved, otherwise false. ### function decode ```cpp bool decode( const String & serialized_content ) ``` Fill the structure from the serialized json object contained in the input string. **Parameters**: * **serialized_content** input string containing the JSON Object **Return**: True if the decoding was successful, otherwise false. ## Public Attributes Documentation ### variable sn ```cpp uint64_t sn; ``` --- # sl::CameraOne This class serves as the primary interface between the camera and the various features provided by the SDK when using Monocular cameras. More... `#include ` ## Detailed Description ```cpp class sl::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 sl::CameraOne class like this: ```cpp #include using namespace sl; int main(int argc, char **argv) { // --- Initialize a CameraOne object and open the ZED // Create a ZED camera object CameraOne zed; // Set configuration parameters InitParametersOne init_params; init_params.camera_resolution = RESOLUTION::HD720; // Use HD720 video mode for USB cameras // init_params.camera_resolution = RESOLUTION::HD1200; // Use HD1200 video mode for GMSL cameras init_params.camera_fps = 60; // Set fps at 60 // Open the camera ERROR_CODE err = zed.open(init_params); if (err != ERROR_CODE::SUCCESS) { std::cout << err << " exit program " << std::endl; return -1; } // --- Main loop grabbing images and depth values // Capture 50 frames and stop int i = 0; Mat image; while (i < 50) { // Grab an image if (zed.grab() == ERROR_CODE::SUCCESS) { // A new image is available if grab() returns SUCCESS // Display a pixel color zed.retrieveImage(image, VIEW::LEFT); // Get the left image sl::uchar4 centerBGRA; image.getValue(image.getWidth() / 2, image.getHeight() / 2, ¢erBGRA); std::cout << "Image " << i << " center pixel B: " << (int)centerBGRA[0] << " G: " << (int)centerBGRA[1] << " R: " << (int)centerBGRA[2] << std::endl; i++; } } // --- Close the Camera zed.close(); return 0; } ``` ## Public Functions Documentation ### function CameraOne ```cpp CameraOne() ``` Default constructor. Creates an empty CameraOne object. Its parameters will be set when calling open() with (optional) desired InitParametersOne. ### function ~CameraOne ```cpp ~CameraOne() ``` Class destructor. The destructor will call the close() function and clear the memory previously allocated by the object. ### function open ```cpp ERROR_CODE open( const InitParametersOne init_parameters =InitParametersOne() ) ``` Opens the camera from the provided InitParametersOne. **Parameters**: * **init_parameters** : 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: **Note**: If this method is called on an already opened camera, close() will be called. ### function isOpened ```cpp bool isOpened() const ``` Reports if the camera has been successfully opened. **Return**: true if the camera is already setup, otherwise false. It has the same behavior as checking if open() returns ERROR_CODE::SUCCESS. ### function getInitParameters ```cpp InitParametersOne getInitParameters() const ``` Returns the InitParametersOne used. **Return**: InitParametersOne containing the parameters used to initialize the CameraOne object. It corresponds to the structure given as argument to the open() method. ### function getCameraInformation ```cpp CameraOneInformation getCameraInformation( Resolution image_size =Resolution(0, 0) ) const ``` Returns the CameraOneInformation associated the camera being used. **Parameters**: * **image_size** : 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 getCameraInformation().camera_configuration.resolution). **Return**: CameraInformation containing the calibration parameters of the ZED, as well as serial number and firmware version. **Note**: * The CameraInformation.camera_configuration will contain two types of calibration parameters: * camera_configuration.calibration_parameters: it contains the calibration for the **undistorted** images. Undistorted images are images that does not have lens distortion. * camera_configuration.calibration_parameters_raw: it contains the original calibration before rectification. * The calibration file SNXXXX.conf can be found in: * **Windows:**_C:/ProgramData/Stereolabs/settings/_ * **Linux:**_/usr/local/zed/settings/_ 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. ### function getCUDAStream ```cpp CUstream getCUDAStream() ``` Gets the Camera-created CUDA stream for sharing it with other CUDA-capable libraries. **Return**: The CUDA stream used for GPU calls. ### function close ```cpp ERROR_CODE close() ``` Close an opened camera. **Note**: To apply a new InitParametersOne, you will need to close the camera first and then open it again with the new InitParametersOne values. 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 effects. ### function getCurrentFPS ```cpp float getCurrentFPS() ``` Returns the current framerate at which the grab() method is successfully called. **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. The returned value is based on the difference of camera timestamps between two successful grab() calls. ### function getTimestamp ```cpp Timestamp getTimestamp( TIME_REFERENCE reference_time ) ``` Returns the timestamp in the requested TIME_REFERENCE. **Parameters**: * **reference_time** : 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 CameraOne instances. This can help to organized the grabbed images in a multi-camera application. * When requesting the TIME_REFERENCE::IMAGE timestamp, the UNIX nanosecond timestamp of the latest 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 1 or 2 frame-time based on the fps (ex: 16.6ms to 33ms 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. ### function read ```cpp ERROR_CODE read() ``` Capture the latest images from the camera and rectify them. **Return**: ERROR_CODE::SUCCESS means that no problem was encountered. **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. * Returned errors can be displayed using toString(). This method is meant to be called frequently in the main loop of your application. ### function grab ```cpp ERROR_CODE grab() ``` This method will call read if hasn't been called already. **Return**: ERROR_CODE::SUCCESS means that no problem was encountered. ### function retrieveImage ```cpp ERROR_CODE retrieveImage( Mat & oMat, VIEW view =VIEW::LEFT, sl::MEM mem =sl::MEM::CPU, Resolution image_size =sl::Resolution(0, 0) ) ``` Retrieves images from the camera. **Parameters**: * **oMat** : The sl::Mat to store the image. The method will create the Mat if necessary at the proper resolution. If already created, it will just update its data. * **view** the desired view, only relates to VIEW::LEFT_XXX as VIEW::LEFT_XXX (lens distortion free, rectified) and VIEW::LEFT_UNRECTIFIED_XXX (with the lens distortion) * **mem** the desired memory type for your output image * **image_size** : If specified, define the resolution of the output sl::Mat. If set to Resolution(0,0), the camera resolution will be taken. Default: (0,0). **Return**: ERROR_CODE::SUCCESS if the method succeeded. **Note**: As this method retrieves the images grabbed by the grab() method, it should be called afterward. **Warning**: A sl::Mat resolution higher than the camera resolution **cannot** be requested. ### function retrieveImage ```cpp ERROR_CODE retrieveImage( RawBuffer & raw_buffer ) ``` Retrieves the raw NvBufSurface buffer for zero-copy access to the native camera capture buffer. **Parameters**: * **raw_buffer** : The RawBuffer to store the buffer reference. **Return**: * ERROR_CODE::SUCCESS if the method succeeded. * ERROR_CODE::CAMERA_NOT_INITIALIZED if the camera is not opened. * ERROR_CODE::FAILURE if no buffer is available. **Note**: As this method retrieves the raw buffer from the grab() method, it should be called afterward. **Warning**: The buffer is automatically released when the RawBuffer goes out of scope. Do NOT manually destroy the NvBufSurface. This method provides direct access to the underlying NvBufSurface buffer without copying data. For mono cameras, only the left buffer is filled; the right buffer will be nullptr. ### function retrieveTensor ```cpp ERROR_CODE retrieveTensor( Tensor & dest, const TensorParameters & params, cudaStream_t stream =0 ) ``` Retrieved a sl::Tensor, containing the input image pre-processed for inference with SVO or live camera. **Parameters**: * **dest** : The Tensor to store the pre-processed input image for inference. * **params** : Options to configure the pre-processing steps applied to the input image. * **stream** : If passed, the CUDA stream to use for GPU calls. 0 by default. **Return**: * ERROR_CODE::SUCCESS if the method succeeded. * ERROR_CODE::INVALID_FUNCTION_PARAMETERS if the provided params are invalid. * ERROR_CODE::CAMERA_NOT_INITIALIZED if the camera is not opened. * ERROR_CODE::FAILURE if another error occurred. **Note**: * This method requires that the camera has been opened in either LIVE mode, SVO mode or STREAM mode. * The retrieved Tensor is allocated on the GPU, so ensure that your system has sufficient GPU memory to accommodate the Tensor size. 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. ### function getSensorsData ```cpp ERROR_CODE getSensorsData( SensorsData & oData, const TIME_REFERENCE reference_time ) ``` Retrieves the SensorsData (IMU) at a specific time reference. **Parameters**: * **oData** : The SensorsData variable to store the data. * **reference_time** : Defines the reference from which you want the data to be expressed. **Return**: ERROR_CODE::SUCCESS if sensors data have been extracted. **Note**: The IMU quaternion (fused data) is given in the specified COORDINATE_SYSTEM of InitParametersOne. * Calling getSensorsData with TIME_REFERENCE::CURRENT gives you the latest sensors data received. Getting all the data requires to call this method at high frame rate in a thread. * Calling getSensorsData with TIME_REFERENCE::IMAGE gives you the sensors data at the time of the latest image grabbed. The delta time between previous and current values can be calculated using `data.imu.timestamp` ### function getSensorsDataBatch ```cpp ERROR_CODE getSensorsDataBatch( std::vector< SensorsData > & oData ) ``` Retrieves all sensor data associated with the most recently grabbed frame. **Parameters**: * **oData** : A vector that will be populated with SensorsData objects associated with the currently grabbed frame. **Return**: ERROR_CODE::SUCCESS if sensors data have been extracted. **Note**: The IMU quaternion (fused data) is expressed in the specified COORDINATE_SYSTEM of InitParametersOne. ### function getCameraSettings ```cpp ERROR_CODE getCameraSettings( VIDEO_SETTINGS settings, int & setting ) ``` Returns the current value of the requested camera setting (gain, brightness, hue, exposure, etc.). **Parameters**: * **settings** : The requested setting. * **setting** : The setting variable to fill. **Return**: ERROR_CODE to indicate if the method was successful. If successful, setting will be filled with the corresponding value. **Note**: * The method works only if the camera is open in LIVE or STREAM mode. * Settings are not exported in the SVO file format. Possible values (range) of each setting are available here. ### function getCameraSettings ```cpp ERROR_CODE getCameraSettings( VIDEO_SETTINGS settings, int & min_val, int & max_val ) ``` Fills the current values of the requested settings for VIDEO_SETTINGS that supports two values (min/max). **Parameters**: * **settings** : The requested setting. * **min_val** : The setting minimum variable to fill. * **max_val** : The setting maximum variable to fill. **Return**: ERROR_CODE to indicate if the method was successful. If successful, setting will be filled with the corresponding value. 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. ### function getCameraSettings ```cpp ERROR_CODE getCameraSettings( VIDEO_SETTINGS settings, Rect & roi ) ``` Overloaded method for VIDEO_SETTINGS::AEC_AGC_ROI which takes a Rect as parameter. **Parameters**: * **settings** : Must be set at VIDEO_SETTINGS::AEC_AGC_ROI, otherwise the method will have no impact. * **roi** : Roi that will be filled. **Return**: ERROR_CODE to indicate if the method was successful. If successful, roi will be filled with the corresponding values. **Note**: * Works only if the camera is open in LIVE or STREAM mode with VIDEO_SETTINGS::AEC_AGC_ROI. * It will return ERROR_CODE::INVALID_FUNCTION_CALL or ERROR_CODE::INVALID_FUNCTION_PARAMETERS otherwise. ### function setCameraSettings ```cpp ERROR_CODE setCameraSettings( VIDEO_SETTINGS settings, int value =VIDEO_SETTINGS_VALUE_AUTO ) ``` Sets the value of the requested camera setting (gain, brightness, hue, exposure, etc.). **Parameters**: * **settings** : The setting to be set. * **value** : The value to set. Default: auto mode **Return**: ERROR_CODE to indicate if the method was successful. **Note**: The method works only if the camera is open in LIVE or STREAM mode. **Warning**: Setting VIDEO_SETTINGS::EXPOSURE or VIDEO_SETTINGS::GAIN to default will automatically sets the other to default. This method only applies for VIDEO_SETTINGS that require a single value. Possible values (range) of each setting are available here. ### function setCameraSettings ```cpp ERROR_CODE setCameraSettings( VIDEO_SETTINGS settings, int min, int max ) ``` Sets the value of the requested camera setting that supports two values (min/max). **Parameters**: * **settings** : The setting to be set. * **min** : The minimum value that can be reached (-1 or 0 gives full range). * **max** : The maximum value that can be reached (-1 or 0 gives full range). **Return**: ERROR_CODE to indicate if the method was successful. **Note**: The method works only if the camera is open in LIVE or STREAM mode. **Warning**: If VIDEO_SETTINGS settings is not supported or min >= max, it will return ERROR_CODE::INVALID_FUNCTION_PARAMETERS. This method only works with the following VIDEO_SETTINGS: * VIDEO_SETTINGS::AUTO_EXPOSURE_TIME_RANGE * VIDEO_SETTINGS::AUTO_ANALOG_GAIN_RANGE * VIDEO_SETTINGS::AUTO_DIGITAL_GAIN_RANGE Possible values (range) of each setting are available here. ### function setCameraSettings ```cpp ERROR_CODE setCameraSettings( VIDEO_SETTINGS settings, Rect roi, bool reset =false ) ``` Overloaded method for VIDEO_SETTINGS::AEC_AGC_ROI which takes a Rect as parameter. **Parameters**: * **settings** : Must be set at VIDEO_SETTINGS::AEC_AGC_ROI, otherwise the method will have no impact. * **roi** : Rect that defines the target to be applied for AEC/AGC computation. Must be given according to camera resolution. * **reset** : Cancel the manual ROI and reset it to the full image. **Return**: ERROR_CODE to indicate if the method was successful. **Note**: Works only if the camera is open in LIVE or STREAM mode with VIDEO_SETTINGS::AEC_AGC_ROI. ### function getCameraSettingsRange ```cpp ERROR_CODE getCameraSettingsRange( VIDEO_SETTINGS settings, int & min, int & max ) ``` Get the range for the specified camera settings VIDEO_SETTINGS as min/max value. **Parameters**: * **settings** : Must be set at a valid VIDEO_SETTINGS that accepts a min/max range and available for the current camera model. * **min** : The minimum value that can be reached to be fill. * **max** : The maximum value that can be reached to be fill. **Return**: ERROR_CODE to indicate if the method was successful. ### function isCameraSettingSupported ```cpp bool isCameraSettingSupported( VIDEO_SETTINGS setting ) ``` Test if the video setting is supported by the camera. **Parameters**: * **setting** : The video setting to test **Return**: true if the VIDEO_SETTINGS is supported by the camera, false otherwise ### function enableRecording ```cpp ERROR_CODE enableRecording( RecordingParameters recording_parameters ) ``` Creates an SVO file to be filled by enableRecording() and disableRecording(). **Parameters**: * **recording_parameters** : 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. 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. ### function getRecordingStatus ```cpp RecordingStatus getRecordingStatus() ``` Get the recording information. **Return**: The recording state structure. For more details, see RecordingStatus. ### function pauseRecording ```cpp void pauseRecording( bool status ) ``` Pauses or resumes the recording. **Parameters**: * **status** : If true, the recording is paused. If false, the recording is resumed. ### function disableRecording ```cpp void disableRecording() ``` Disables the recording initiated by enableRecording() and closes the generated file. **Note**: This method will automatically be called by close() if enableRecording() was called. ### function getFrameDroppedCount ```cpp unsigned int getFrameDroppedCount() ``` Returns the number of frames dropped since grab() was called for the first time. **Return**: The number of frames dropped since the first grab() call. 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). ### function getSVOPosition ```cpp int getSVOPosition() ``` Returns the current playback position in the SVO file. **See**: setSVOPosition() for an example. **Return**: The current frame position in the SVO file. Returns -1 if the SDK is not reading an SVO. **Note**: The method works only if the camera is open in SVO playback mode. 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). ### function getSVOPositionAtTimestamp ```cpp int getSVOPositionAtTimestamp( const sl::Timestamp & timestamp ) ``` Retrieves the frame index within the SVO file corresponding to the provided timestamp. **Parameters**: * **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. ### function setSVOPosition ```cpp ERROR_CODE setSVOPosition( int position ) ``` Sets the playback cursor to the desired frame number in the SVO file. **Parameters**: * **position** : The position to set the SVO cursor to. **Return**: ERROR_CODE to indicate if the method was successful. **Note**: The method works only if the camera is open in SVO playback mode. This method allows you to move around within a played-back SVO file. After calling, the next call to grab() will read the provided frame number. ### function getSVONumberOfFrames ```cpp int getSVONumberOfFrames() ``` Returns the number of frames in the SVO file. **See**: setSVOPosition() for an example. **Return**: The total number of frames in the SVO file. -1 if the SDK is not reading a SVO. **Note**: The method works only if the camera is open in SVO playback mode. ### function ingestDataIntoSVO ```cpp ERROR_CODE ingestDataIntoSVO( const sl::SVOData & data ) ``` Ingest SVOData in a SVO file. **Parameters**: * **data** : Data to ingest in the SVO file. **Return**: [sl::ERROR_CODE::SUCCESS] in case of success, [sl::ERROR_CODE::FAILURE] otherwise. **Note**: The method works only if the camera is recording. ### function retrieveSVOData ```cpp ERROR_CODE retrieveSVOData( const std::string & key, std::map< sl::Timestamp, sl::SVOData > & data, sl::Timestamp ts_begin =0, sl::Timestamp ts_end =0 ) const ``` Retrieves SVO data from the SVO file at the given channel key and in the given timestamp range. **Parameters**: * **key** : The key of the SVOData that is going to be retrieved. * **data** : The map to be filled with SVOData objects, with timestamps as keys. * **ts_begin** : The beginning of the range. * **ts_end** : The end of the range. **Return**: [sl::ERROR_CODE::SUCCESS] in case of success, [sl::ERROR_CODE::FAILURE] otherwise. **Note**: The method works only if the camera is in SVO mode. ### function getSVODataKeys ```cpp std::vector< std::string > getSVODataKeys() const ``` Get the external channels that can be retrieved from the SVO file. **Return**: List of available keys. **Note**: The method returns an empty std::vector if not in SVO mode. ### function enableStreaming ```cpp ERROR_CODE enableStreaming( StreamingParameters streaming_parameters =StreamingParameters() ) ``` Creates a streaming pipeline. **Parameters**: * **streaming_parameters** : A structure containing all the specific parameters for the streaming. Default: a reset of StreamingParameters . **Return**: * ERROR_CODE::SUCCESS if streaming was successfully started. * ERROR_CODE::INVALID_FUNCTION_CALL if open() was not successfully called before. * ERROR_CODE::FAILURE if streaming RTSP protocol was not able to start. * ERROR_CODE::NO_GPU_COMPATIBLE if streaming codec is not supported (in this case, use H264 codec which is supported on all NVIDIA GPU the ZED SDK supports). ### function disableStreaming ```cpp void disableStreaming() ``` Disables the streaming initiated by enableStreaming(). **Note**: This method will automatically be called by close() if enableStreaming() was called. See enableStreaming() for an example. ### function isStreamingEnabled ```cpp bool isStreamingEnabled() ``` Tells if the streaming is running. **Return**: true if the stream is running, false otherwise. ### function getStreamingParameters ```cpp StreamingParameters getStreamingParameters() ``` Returns the StreamingParameters used. **Return**: StreamingParameters containing the parameters used for streaming initialization. It corresponds to the structure given as argument to the enableStreaming() method. ### function reboot ```cpp static ERROR_CODE reboot() ``` Performs a hardware reset of the CameraOne. **Return**: * ERROR_CODE::SUCCESS if everything went fine. * ERROR_CODE::FAILURE otherwise. ### function getDeviceList ```cpp static std::vector< sl::DeviceProperties > getDeviceList( void ) ``` List all the connected devices with their associated information. **Return**: The device properties for each connected camera. **Warning**: As this method returns an std::vector, it is only safe to use in Release or ReleaseWithDebugInfos mode (not Debug). This is due to a known compatibility issue between release (the SDK) and debug (your app) implementations of std::vector. This method lists all the cameras available and provides their serial number, models and other information. ### function setTimestampClock ```cpp static void setTimestampClock( TIMESTAMP_CLOCK clock ) ``` Sets the clock source used for all SDK timestamps (images and sensors). **Parameters**: * **clock** : The desired sl::TIMESTAMP_CLOCK. **Note**: Call this before opening any camera. This is a process-wide setting shared by all Camera and CameraOne instances. ### function getTimestampClock ```cpp static TIMESTAMP_CLOCK getTimestampClock() ``` Returns the clock source currently used for SDK timestamps. **Return**: The active sl::TIMESTAMP_CLOCK. ### function setMaxSystemClockStepMs ```cpp static void setMaxSystemClockStepMs( float limit_ms ) ``` 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::setMaxSystemClockStepMs() for the full cheat sheet. ### function getMaxSystemClockStepMs ```cpp static float getMaxSystemClockStepMs() ``` Returns the current system-clock step clamp in milliseconds. ### function getStreamingDeviceList ```cpp static std::vector< sl::StreamingProperties > getStreamingDeviceList() ``` List all the streaming devices with their associated information. **Return**: The streaming properties for each connected camera. **Warning**: * As this method returns an std::vector, it is only safe to use in Release or ReleaseWithDebugInfos mode (not Debug). This is due to a known compatibility issue between release (the SDK) and debug (your app) implementations of std::vector. * This method takes around 2 seconds to make sure all network informations has been captured. Make sure to run this method in a thread. --- # sl::Chunk **Module:** **Spatial Mapping Module** Class representing a sub-mesh containing local vertices and triangles. More... `#include ` ## Detailed Description ```cpp class sl::Chunk; ``` Class representing a sub-mesh containing local vertices and triangles. **Note**: uv contains data only if your mesh have textures (by loading it or after calling sl::Mesh.applyTexture()). Vertices and normals have the same size and are linked by id stored in triangles. ## Public Functions Documentation ### function Chunk ```cpp Chunk() ``` Default constructor. Creates an empty sl::Chunk. ### function ~Chunk ```cpp ~Chunk() ``` Default destructor. ### function clear ```cpp void clear() ``` Clears all data. ## Public Attributes Documentation ### variable vertices ```cpp std::vector< float3 > vertices; ``` Vector of vertices. Vertices are defined by a 3D point `{x, y, z}`. ### variable triangles ```cpp std::vector< uint3 > triangles; ``` Vector of triangles/faces. Triangles are defined as a set of three vertices indexes `{v1, v2, v3}`. ### variable normals ```cpp std::vector< float3 > normals; ``` Vector of normals. **Note**: A normal is defined for each vertex. Normals are defined by three components `{nx, ny, nz}`. ### variable colors ```cpp std::vector< uchar3 > colors; ``` Vector of colors. **Note**: A color is defined for each vertex. Colors are defined by three components `{b, g, r}`. ### variable uv ```cpp std::vector< float2 > uv; ``` UVs defines the 2D projection of each vertices onto the texture. **Note**: Contains data only if your mesh has textures (by loading it or calling sl::Mesh.applyTexture()). 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. ### variable timestamp ```cpp unsigned long long timestamp; ``` Timestamp of the latest update. ### variable barycenter ```cpp float3 barycenter; ``` 3D centroid of the chunk. ### variable has_been_updated ```cpp bool has_been_updated; ``` Whether the point cloud chunk has been updated by an inner process. --- # sl::CommunicationParameters **Module:** **Fusion Module** Holds the communication parameter to configure the connection between senders and receiver. `#include ` ## Public Types Documentation ### enum COMM_TYPE | Enumerator | Value | Description | | ---------- | ----- | ----------- | | 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. | Lists the different types of communications available for Fusion module. ## Public Functions Documentation ### function CommunicationParameters ```cpp CommunicationParameters() ``` Default constructor. All the parameters are set to their default and optimized values. ### function setForSharedMemory ```cpp void setForSharedMemory() ``` Setup the communication to used shared memory for intra process workflow, senders and receiver in different threads. ### function setForLocalNetwork ```cpp void setForLocalNetwork( int port ) ``` Setup local Network connection information, sender side, only the port is required. ### function setForLocalNetwork ```cpp void setForLocalNetwork( std::string ip_address, int port ) ``` Setup local Network connection information, receiver side, need the edge device IP and the port. ### function getPort ```cpp inline int getPort() const ``` This function returns the comm port used for streaming the data. **Return**: the port ### function getIpAddress ```cpp inline std::string getIpAddress() const ``` This function returns the IP address of the sender. **Return**: the IP address ### function getType ```cpp inline COMM_TYPE getType() const ``` This function returns the type of the used communication. **Return**: the COMM_TYPE of the communication used --- # sl::CustomBoxObjectData **Module:** **Object Detection Module** Class that store externally detected objects. More... `#include ` ## Detailed Description ```cpp class sl::CustomBoxObjectData; ``` Class that store externally detected objects. The objects can be ingested with sl::Camera.ingestCustomBoxObjects() to extract 3D and tracking information over time. ## Public Functions Documentation ### function CustomBoxObjectData ```cpp CustomBoxObjectData() ``` Default constructor. ## Public Attributes Documentation ### variable unique_object_id ```cpp String unique_object_id; ``` Unique id to help identify and track AI detections. It can be either generated externally, or by using generate_unique_id() or left empty. ### variable bounding_box_2d ```cpp std::vector< sl::uint2 > bounding_box_2d; ``` 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. ```cpp A ------ B | Object | D ------ C ``` ### variable label ```cpp int label; ``` Object label. **Note**: It should define an object class. This means that any similar object (in classification) should share the same label number. This information is passed-through and can be used to improve object tracking. ### variable probability ```cpp float probability; ``` Detection confidence value of the object. **Note**: * The value should be in `[0-1]`. * It can be used to improve the object tracking. ### variable is_grounded ```cpp bool is_grounded = true; ``` Provide hypothesis about the object movements (degrees of freedom or DoF) to improve the object tracking. **Note**: * This parameter cannot be changed for a given object tracking id. * It is advised to set it by labels to avoid issues. * 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). ### variable is_static ```cpp bool is_static = false; ``` 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. ### variable tracking_timeout ```cpp float tracking_timeout = -1.F; ``` 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. ### variable tracking_max_dist ```cpp float tracking_max_dist = -1.F; ``` 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. ### variable max_box_width_meters ```cpp float max_box_width_meters = -1.F; ``` 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) ### variable min_box_width_meters ```cpp float min_box_width_meters = -1.F; ``` 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) ### variable max_box_height_meters ```cpp float max_box_height_meters = -1.F; ``` 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) ### variable min_box_height_meters ```cpp float min_box_height_meters = -1.F; ``` 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) ### variable max_allowed_acceleration ```cpp float max_allowed_acceleration = std::numeric_limits::quiet_NaN(); ``` Expected maximum acceleration of the tracked object. Determines how the ZED SDK interprets object acceleration, affecting tracking behavior and predictions. Takes precedence over the runtime parameter, if also set. By default, let the ZED SDK interpret the object acceleration. Unit is m/s^2. ### variable velocity_smoothing_factor ```cpp float velocity_smoothing_factor = -1.F; ``` 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. A negative value (e.g. -1) lets the ZED SDK interpret the velocity smoothing factor. Default: -1 ### variable min_velocity_threshold ```cpp float min_velocity_threshold = -1.F; ``` 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 minimum velocity threshold. ### variable prediction_timeout_s ```cpp float prediction_timeout_s = -1.F; ``` 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. Default: -1 ### variable min_confirmation_time_s ```cpp float min_confirmation_time_s = -1.F; ``` 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 minimum confirmation time. Default: -1. --- # sl::CustomMaskObjectData **Module:** **Object Detection Module** Class that store externally detected objects with mask. More... `#include ` ## Detailed Description ```cpp class sl::CustomMaskObjectData; ``` Class that store externally detected objects with mask. The objects can be ingested with sl::Camera.ingestCustomMaskObjects() to extract 3D and tracking information over time. ## Public Functions Documentation ### function CustomMaskObjectData ```cpp CustomMaskObjectData() ``` Default constructor. ## Public Attributes Documentation ### variable unique_object_id ```cpp String unique_object_id; ``` Unique id to help identify and track AI detections. It can be either generated externally, or by using generate_unique_id() or left empty. ### variable bounding_box_2d ```cpp std::vector< sl::uint2 > bounding_box_2d; ``` 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. ```cpp A ------ B | Object | D ------ C ``` ### variable label ```cpp int label; ``` Object label. **Note**: It should define an object class. This means that any similar object (in classification) should share the same label number. This information is passed-through and can be used to improve object tracking. ### variable probability ```cpp float probability; ``` Detection confidence value of the object. **Note**: * The value should be in `[0-1]`. * It can be used to improve the object tracking. ### variable is_grounded ```cpp bool is_grounded = true; ``` Provide hypothesis about the object movements (degrees of freedom or DoF) to improve the object tracking. **Note**: * This parameter cannot be changed for a given object tracking id. * It is advised to set it by labels to avoid issues. * 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). ### variable is_static ```cpp bool is_static = false; ``` 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. ### variable tracking_timeout ```cpp float tracking_timeout = -1.F; ``` 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. ### variable tracking_max_dist ```cpp float tracking_max_dist = -1.F; ``` 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. ### variable max_box_width_meters ```cpp float max_box_width_meters = -1.F; ``` 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) ### variable min_box_width_meters ```cpp float min_box_width_meters = -1.F; ``` 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) ### variable max_box_height_meters ```cpp float max_box_height_meters = -1.F; ``` 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) ### variable min_box_height_meters ```cpp float min_box_height_meters = -1.F; ``` 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) ### variable max_allowed_acceleration ```cpp float max_allowed_acceleration = std::numeric_limits::quiet_NaN(); ``` Expected maximum acceleration of the tracked object. Determines how the ZED SDK interprets object acceleration, affecting tracking behavior and predictions. Takes precedence over the runtime parameter, if also set. By default, let the ZED SDK interpret the object acceleration. Unit is m/s^2. ### variable velocity_smoothing_factor ```cpp float velocity_smoothing_factor = -1.F; ``` 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. A negative value (e.g. -1) lets the ZED SDK interpret the velocity smoothing factor. Default: -1 ### variable min_velocity_threshold ```cpp float min_velocity_threshold = -1.F; ``` 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 minimum velocity threshold. Default: -1. ### variable prediction_timeout_s ```cpp float prediction_timeout_s = -1.F; ``` 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. Default: -1 ### variable min_confirmation_time_s ```cpp float min_confirmation_time_s = -1.F; ``` 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 minimum confirmation time. Default: -1. ### variable box_mask ```cpp sl::Mat box_mask; ``` 2D mask of the object inside its bounding box. --- # sl::ECEF **Module:** **Fusion Module** Represents a world position in ECEF format. `#include ` ## Public Attributes Documentation ### variable x ```cpp double x; ``` x coordinate of ECEF. ### variable y ```cpp double y; ``` y coordinate of ECEF. ### variable z ```cpp double z; ``` z coordinate of ECEF. --- # sl::ENU **Module:** **Fusion Module** Represents a world position in ENU format. `#include ` ## Public Attributes Documentation ### variable east ```cpp double east; ``` East coordinate. ### variable north ```cpp double north; ``` North coordinate. ### variable up ```cpp double up; ``` Up coordinate. --- # sl::FusedPointCloud **Module:** **Spatial Mapping Module** Class representing a fused point cloud and containing the geometric and color data of the scene captured by the spatial mapping module. More... `#include ` ## Detailed Description ```cpp class sl::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. ## Public Types Documentation ### typedef chunkList ```cpp typedef std::vector chunkList; ``` Vector of chunks id. ## Public Functions Documentation ### function FusedPointCloud ```cpp FusedPointCloud() ``` Default constructor. Creates an empty sl::FusedPointCloud. ### function ~FusedPointCloud ```cpp ~FusedPointCloud() ``` Default destructor. ### function operator[] ```cpp PointCloudChunk & operator[]( int index ) ``` Defines the [] operator to directly access the desired chunk. ### function getNumberOfPoints ```cpp size_t getNumberOfPoints() ``` Computes the total number of points stored in all chunks. **Return**: The number of points stored in all chunks. ### function updateFromChunkList ```cpp void updateFromChunkList( chunkList IDs =chunkList() ) ``` Updates vertices and normals from chunk data pointed by the given sl::Mesh::chunkList. **Parameters**: * **IDs** : Indices of chunks which will be concatenated. Default: (empty). **Note**: If the given sl::FusedPointCloud::chunkList is empty, all chunks will be used to update the current sl::FusedPointCloud. ### function save ```cpp bool save( String filename, MESH_FILE_FORMAT type =MESH_FILE_FORMAT::OBJ, chunkList IDs =chunkList() ) ``` Saves the current sl::FusedPointCloud into a file. **Parameters**: * **filename** : Path of the file to store the fused point cloud in. * **type** : File extension type. Default: sl::MESH_FILE_FORMAT::OBJ. * **IDs** : 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. * This way you can save different parts of your sl::FusedPointCloud by updating it with updateFromChunkList(). ### function load ```cpp bool load( String filename, bool update_chunk_only =false ) ``` Loads the fused point cloud from a file. **Parameters**: * **filename** : Path of the file to load the fused point cloud from. * **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. ### function clear ```cpp void clear() ``` Clears all the data. ## Public Attributes Documentation ### variable chunks ```cpp std::vector< PointCloudChunk > chunks; ``` List of chunks constituting the sl::FusedPointCloud. ### variable vertices ```cpp std::vector< float4 > vertices; ``` Vector of vertices. Vertices are defined by a colored 3D point `{x, y, z, rgba}`. ### variable normals ```cpp std::vector< float3 > normals; ``` Vector of normals. Normals are defined by three components `{nx, ny, nz}`. --- # sl::FusedPositionalTrackingStatus **Module:** **Positional Tracking Module** Class containing the overall position fusion status. `#include ` ## Public Attributes Documentation ### variable odometry_status ```cpp ODOMETRY_STATUS odometry_status; ``` Represents the current state of Visual-Inertial Odometry (VIO) tracking between the previous frame and the current frame. ### variable spatial_memory_status ```cpp SPATIAL_MEMORY_STATUS spatial_memory_status; ``` Represents the current state of camera tracking in the global map. ### variable gnss_status ```cpp GNSS_STATUS gnss_status = sl::GNSS_STATUS::UNKNOWN; ``` Represents the current status of GNSS. ### variable gnss_mode ```cpp GNSS_MODE gnss_mode = sl::GNSS_MODE::UNKNOWN; ``` Represents the current mode of GNSS. ### variable gnss_fusion_status ```cpp GNSS_FUSION_STATUS gnss_fusion_status; ``` Represents the current state of GNSS fusion for global localization. ### variable tracking_fusion_status ```cpp POSITIONAL_TRACKING_FUSION_STATUS tracking_fusion_status; ``` Represents the current state of positional tracking fusion. --- # sl::Fusion **Module:** **Fusion Module** Holds Fusion process data and functions. `#include ` ## Public Functions Documentation ### function Fusion ```cpp Fusion() ``` Default constructor. ### function ~Fusion ```cpp ~Fusion() ``` Default destructor. ### function init ```cpp FUSION_ERROR_CODE init( sl::InitFusionParameters init_parameters =InitFusionParameters() ) ``` Initialize the fusion module with the requested parameters. **Parameters**: * **init_parameters** Initialization parameters. **Return**: SUCCESS if it goes as it should, otherwise it returns an FUSION_ERROR_CODE. ### function close ```cpp void close() ``` Will deactivate all the fusion modules and free internal data. ### function subscribe ```cpp FUSION_ERROR_CODE subscribe( const sl::FusionConfiguration & fusion_config ) ``` Set the specified camera as a data provider. **Parameters**: * **fusion_config** The fusion configuration parameters. **Return**: SUCCESS if it goes as it should, otherwise it returns an FUSION_ERROR_CODE. ### function subscribe ```cpp FUSION_ERROR_CODE subscribe( CameraIdentifier uuid, CommunicationParameters param =CommunicationParameters(), sl::Transform pose =sl::Transform(), bool override_gravity =false ) override ``` Set the specified camera as a data provider. **Parameters**: * **uuid** The requested camera identifier. * **param** The communication parameters to connect to the camera. * **pose** The World position of the camera, regarding the other camera of the setup. * **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**: SUCCESS if it goes as it should, otherwise it returns an FUSION_ERROR_CODE. **Warning**: deprecated, FUSION_ERROR_CODE Fusion::subscribe(const sl::FusionConfiguration &fusion_config) should be used instead ### function unsubscribe ```cpp FUSION_ERROR_CODE unsubscribe( CameraIdentifier uuid ) ``` Remove the specified camera from data provider. **Parameters**: * **uuid** The requested camera identifier.. **Return**: SUCCESS if it goes as it should, otherwise it returns an FUSION_ERROR_CODE. ### function updatePose ```cpp FUSION_ERROR_CODE updatePose( CameraIdentifier uuid, sl::Transform pose ) ``` Updates the specified camera position inside fusion WORLD. **Parameters**: * **uuid** The requested camera identifier. * **pose** The World position of the camera, regarding the other camera of the setup. **Return**: SUCCESS if it goes as it should, otherwise it returns an FUSION_ERROR_CODE. ### function getPose ```cpp FUSION_ERROR_CODE getPose( CameraIdentifier uuid, sl::Transform & pose ) ``` Get the specified camera position inside fusion WORLD. **Parameters**: * **uuid** The requested camera identifier. * **pose** The World position of the camera, regarding the other camera of the setup. **Return**: SUCCESS if it goes as it should, otherwise it returns an FUSION_ERROR_CODE. ### function getProcessMetrics ```cpp FUSION_ERROR_CODE getProcessMetrics( FusionMetrics & metrics ) ``` Get the metrics of the Fusion process, for the fused data as well as individual camera provider data. **Parameters**: * **metrics** The process metrics. **Return**: SUCCESS if it goes as it should, otherwise it returns an FUSION_ERROR_CODE. ### function getSenderState ```cpp std::map< CameraIdentifier, SENDER_ERROR_CODE > getSenderState() ``` Returns the state of each connected data senders. **Return**: The individual state of each connected senders. ### function process ```cpp FUSION_ERROR_CODE process() ``` Runs the main function of the Fusion, this trigger the retrieve and synchronization of all connected senders and updates the enabled modules. **Return**: SUCCESS if it goes as it should, otherwise it returns an FUSION_ERROR_CODE. ### function retrieveImage ```cpp FUSION_ERROR_CODE retrieveImage( sl::Mat & mat, CameraIdentifier uuid, sl::Resolution resolution =sl::Resolution(0, 0) ) ``` Returns the current [sl::VIEW::LEFT] of the specified camera, the data is synchronized. **Parameters**: * **mat** the CPU BGRA image of the requested camera. * **uuid** the requested camera identifier. * **resolution** the requested resolution of the output image, can be lower or equal (default) to the original image resolution. **Return**: SUCCESS if it goes as it should, otherwise it returns an FUSION_ERROR_CODE. **Note**: Only the Left BGRA image is available. **Warning**: This feature is not available for network cameras. ### function retrieveMeasure ```cpp FUSION_ERROR_CODE retrieveMeasure( sl::Mat & mat, CameraIdentifier uuid, sl::MEASURE measure =sl::MEASURE::DEPTH, sl::Resolution resolution =sl::Resolution(0, 0), sl::FUSION_REFERENCE_FRAME reference_frame =sl::FUSION_REFERENCE_FRAME::BASELINK ) ``` Returns the current measure of the specified camera, the data is synchronized. **Parameters**: * **mat** the CPU data of the requested camera. * **uuid** the requested camera identifier. * **measure** the requested measure type, by default DEPTH (F32_C1) * **resolution** the requested resolution of the output image, can be lower or equal (default) to the original image resolution. * **reference_frame** the requested reference frame, by default BASELINK. it is only available for fused point clouds **Return**: SUCCESS if it goes as it should, otherwise it returns an FUSION_ERROR_CODE. **Note**: Only MEASURE: DEPTH, XYZ, XYZRGBA, XYZBGRA, XYZARGB, XYZABGR, DEPTH_U16_MM are available. **Warning**: This feature is not available for network cameras. ### function enableBodyTracking ```cpp FUSION_ERROR_CODE enableBodyTracking( const BodyTrackingFusionParameters & params =BodyTrackingFusionParameters() ) ``` Enables the body tracking fusion module. **Parameters**: * **params** Structure containing all specific parameters for body tracking fusion. For more information, see the BodyTrackingFusionParameters documentation. **Return**: SUCCESS if it goes as it should, otherwise it returns an FUSION_ERROR_CODE. ### function retrieveBodies ```cpp FUSION_ERROR_CODE retrieveBodies( sl::Bodies & objs, BodyTrackingFusionRuntimeParameters parameters =BodyTrackingFusionRuntimeParameters(), CameraIdentifier uuid =CameraIdentifier(), sl::FUSION_REFERENCE_FRAME reference_frame =sl::FUSION_REFERENCE_FRAME::BASELINK ) ``` Retrieves the body data, can be the fused data (default), or the raw data provided by a specific sender. **Parameters**: * **objs** The fused bodies will be saved into this objects. * **parameters** Body detection runtime settings, can be changed at each detection. * **uuid** If set to a sender serial number (different from 0), this will retrieve the raw data provided by this sender. * **reference_frame** The reference frame in which the objects will be expressed. Default: FUSION_REFERENCE_FRAME::BASELINK. **Return**: SUCCESS if it goes as it should, otherwise it returns an FUSION_ERROR_CODE. ### function disableBodyTracking ```cpp void disableBodyTracking() ``` Disable the body fusion tracking module. ### function enableObjectDetection ```cpp FUSION_ERROR_CODE enableObjectDetection( const ObjectDetectionFusionParameters & params =ObjectDetectionFusionParameters() ) ``` Enables the object detection fusion module. **Parameters**: * **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. ### function retrieveObjects ```cpp FUSION_ERROR_CODE retrieveObjects( std::unordered_map< sl::String, sl::Objects > & objs, sl::FUSION_REFERENCE_FRAME reference_frame =sl::FUSION_REFERENCE_FRAME::BASELINK ) ``` Retrieves all the fused objects data. **Parameters**: * **objs** The fused objects will be saved into this objects. * **reference_frame** The reference frame in which the objects will be expressed. Default: FUSION_REFERENCE_FRAME::BASELINK. **Return**: SUCCESS if it goes as it should, otherwise it returns a FUSION_ERROR_CODE. ### function retrieveObjects ```cpp FUSION_ERROR_CODE retrieveObjects( sl::Objects & objs, const sl::String & fused_od_group_name, sl::FUSION_REFERENCE_FRAME reference_frame =sl::FUSION_REFERENCE_FRAME::BASELINK ) ``` Retrieves the fused objects of a given fused OD group. **Parameters**: * **objs** The fused objects will be saved into this objects. * **fused_od_group_name** The name of the fused objects group to retrieve. * **reference_frame** The reference frame in which the objects will be expressed. Default: FUSION_REFERENCE_FRAME::BASELINK. **Return**: SUCCESS if it goes as it should, otherwise it returns a FUSION_ERROR_CODE. ### function retrieveObjects ```cpp FUSION_ERROR_CODE retrieveObjects( std::unordered_map< unsigned int, sl::Objects > & objs, const CameraIdentifier & uuid ) ``` Retrieves all the raw objects data provided by a specific sender. **Parameters**: * **objs** The fused objects will be saved into this objects. * **uuid** Retrieve the raw data provided by this sender. **Return**: SUCCESS if it goes as it should, otherwise it returns a FUSION_ERROR_CODE. ### function retrieveObjects ```cpp FUSION_ERROR_CODE retrieveObjects( sl::Objects & objs, const CameraIdentifier & uuid, const unsigned int instance_id ) ``` Retrieves the raw objects data provided by a specific sender and a specific instance id. **Parameters**: * **objs** The fused objects will be saved into this objects. * **uuid** Retrieve the raw data provided by this sender. * **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. ### function disableObjectDetection ```cpp void disableObjectDetection() ``` Disable the object detection fusion module. ### function enablePositionalTracking ```cpp FUSION_ERROR_CODE enablePositionalTracking( PositionalTrackingFusionParameters parameters =PositionalTrackingFusionParameters() ) ``` Enables positional tracking fusion module. **Parameters**: * **parameters** A structure containing all the PositionalTrackingFusionParameters that define positional tracking fusion module. **Return**: SUCCESS if it goes as it should, otherwise it returns an FUSION_ERROR_CODE. ### function getPosition ```cpp POSITIONAL_TRACKING_STATE getPosition( Pose & camera_pose, sl::REFERENCE_FRAME reference_frame =REFERENCE_FRAME::WORLD, CameraIdentifier uuid =CameraIdentifier(), POSITION_TYPE position_type =POSITION_TYPE::FUSION ) ``` Get the Fused Position referenced to the first camera subscribed. If `uuid` is specified then project position on the referenced camera. **Parameters**: * **camera_pose** Will contain the fused position referenced by default in world (world is given by the calibration of the cameras system). * **reference_frame** Defines the reference from which you want the pose to be expressed. Default : REFERENCE_FRAME::WORLD. * **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. * **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. ### function getFusedPositionalTrackingStatus ```cpp FusedPositionalTrackingStatus getFusedPositionalTrackingStatus() ``` Get the current status of fused position. **Return**: FusedPositionalTrackingStatus is the current status of the tracking process. ### function ingestGNSSData ```cpp FUSION_ERROR_CODE ingestGNSSData( sl::GNSSData gnss_data ) ``` Ingest GNSS data from an external sensor into the fusion module. **Parameters**: * **gnss_data** The current GNSS data to combine with the current positional tracking data. **Return**: SUCCESS if it goes as it should, otherwise it returns an FUSION_ERROR_CODE. ### function getCurrentGNSSData ```cpp POSITIONAL_TRACKING_STATE getCurrentGNSSData( sl::GNSSData & out ) ``` Returns the last synchronized gnss data. **Parameters**: * **out** Last synchronized gnss data. **Return**: POSITIONAL_TRACKING_STATE is the current state of the tracking process. ### function getGeoPose ```cpp GNSS_FUSION_STATUS getGeoPose( sl::GeoPose & pose ) ``` Returns the current GeoPose. **Parameters**: * **pose** The current GeoPose. **Return**: GNSS_FUSION_STATUS is the current state of the tracking process. ### function Geo2Camera ```cpp GNSS_FUSION_STATUS Geo2Camera( sl::LatLng & in, sl::Pose & out ) ``` Convert latitude / longitude into position in sl::Fusion coordinate system. **Parameters**: * **in** The latitude / longitude to be converted in sl::Fusion coordinate system. * **out** Converted position in sl::Fusion coordinate system. **Return**: GNSS_FUSION_STATUS is the current state of the tracking process. ### function Camera2Geo ```cpp GNSS_FUSION_STATUS Camera2Geo( sl::Pose const & in, sl::GeoPose & out ) ``` Convert a position in sl::Fusion coordinate system in global world coordinate. **Parameters**: * **in** Position to convert in global world coordinate. * **out** Converted position in global world coordinate. **Return**: GNSS_FUSION_STATUS is the current state of the tracking process. ### function ENU2Geo ```cpp FUSION_ERROR_CODE ENU2Geo( const sl::ENU & in, sl::LatLng & out ) const ``` Convert a ENU position expressed inside the Fusion coordinate system to a global world coordinate. **Parameters**: * **in** Input enu coordinate. * **out** Converted position in lat/lng coordinate system. **Return**: FUSION_ERROR_CODE FAILURE if the conversion failed, SUCCESS otherwise. ### function Geo2ENU ```cpp FUSION_ERROR_CODE Geo2ENU( const sl::LatLng & in, sl::ENU & out ) const ``` Convert a global world coordinate to a ENU position expressed inside the Fusion coordinate system. **Parameters**: * **in** Input lat/lng coordinate. * **out** Converted position in ENU coordinate system. **Return**: FUSION_ERROR_CODE FAILURE if the conversion failed, SUCCESS otherwise. ### function disablePositionalTracking ```cpp void disablePositionalTracking() ``` Disable the fusion positional tracking module. ### function getCurrentTimeStamp ```cpp sl::Timestamp getCurrentTimeStamp() ``` Return the current fusion timestamp, aligned with the synchronized GNSS and camera data. **Return**: sl::Timestamp current fusion timestamp. ### function getCurrentGNSSCalibrationSTD ```cpp GNSS_FUSION_STATUS getCurrentGNSSCalibrationSTD( float & yaw_std, sl::float3 & position_std ) ``` Get the current calibration uncertainty obtained during calibration process. **Parameters**: * **yaw_std** Output yaw uncertainty in radian. * **position_std** Output position uncertainty in meter. **Return**: sl::GNSS_FUSION_STATUS representing current initialisation status. ### function getGeoTrackingCalibration ```cpp sl::Transform getGeoTrackingCalibration() ``` Get the calibration found between VIO and GNSS. **Return**: sl::Transform is the calibration found between VIO and GNSS during calibration process. ### function enableSpatialMapping ```cpp FUSION_ERROR_CODE enableSpatialMapping( SpatialMappingFusionParameters parameters =SpatialMappingFusionParameters() ) ``` Initializes and starts the spatial mapping processes. **Parameters**: * **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::FAILURE otherwise. **Note**: * The tracking (enablePositionalTracking()) needs to be enabled to use the spatial mapping. * Lower SpatialMappingFusionParameters.range_meter and SpatialMappingFusionParameters.resolution_meter for higher performance. **Warning**: This fuction is only available for INTRA_PROCESS communication type. 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 retrieveSpatialMapAsync(). Note that retrieveSpatialMapAsync() should be called after requestSpatialMapAsync(). ### function requestSpatialMapAsync ```cpp void requestSpatialMapAsync() ``` Starts the spatial map generation process in a non blocking thread from the spatial mapping process. **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. 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 getSpatialMapRequestStatusAsync(), and retrieve the mesh using retrieveSpatialMapAsync. ### function getSpatialMapRequestStatusAsync ```cpp FUSION_ERROR_CODE getSpatialMapRequestStatusAsync() ``` Returns the spatial map generation status. This status allows to know if the mesh can be retrieved by calling retrieveSpatialMapAsync. **Return**: SUCCESS if the mesh is ready and not yet retrieved, otherwise FUSION_ERROR_CODE::FAILURE. See requestSpatialMapAsync() for an example. ### function retrieveSpatialMapAsync ```cpp FUSION_ERROR_CODE retrieveSpatialMapAsync( Mesh & mesh ) ``` Retrieves the current generated spatial map only if SpatialMappingParameters::map_type was set as SPATIAL_MAP_TYPE::MESH. **Parameters**: * **mesh** : **The** mesh to be filled with the generated spatial map. **Return**: SUCCESS if the mesh is retrieved, otherwise FUSION_ERROR_CODE::FAILURE. **Note**: This function only updates the necessary chunks and adds the new ones in order to improve update speed. **Warning**: * You should not modify the mesh between two calls of this function, otherwise it can lead to corrupted mesh. * If the SpatialMappingParameters::map_type has not been setup as SPATIAL_MAP_TYPE::MESH, the object will be empty. See requestSpatialMapAsync() for an example. After calling requestSpatialMapAsync , this function allows you to retrieve the generated mesh. ### function retrieveSpatialMapAsync ```cpp FUSION_ERROR_CODE retrieveSpatialMapAsync( FusedPointCloud & fpc ) ``` Retrieves the current generated spatial map only if SpatialMappingParameters::map_type was set as SPATIAL_MAP_TYPE::FUSED_POINT_CLOUD. After calling requestSpatialMapAsync , this function allows you to retrieve the generated fused point cloud. **Parameters**: * **fpc** : **The** fused point cloud to be filled with the generated spatial map. **Return**: SUCCESS if the fused point cloud is retrieved, otherwise FUSION_ERROR_CODE::FAILURE. **Note**: This function only updates the necessary chunks and adds the new ones in order to improve update speed. **Warning**: * You should not modify the fused point cloud between two calls of this function, otherwise it can lead to a corrupted fused point cloud. * If the SpatialMappingParameters::map_type has not been setup as SPATIAL_MAP_TYPE::FUSED_POINT_CLOUD, the object will be empty. See requestSpatialMapAsync() for an example. ### function disableSpatialMapping ```cpp void disableSpatialMapping() ``` Disables the spatial mapping process. **Note**: This function frees the memory allocated for the spatial mapping, consequently, the spatial map cannot be retrieved after this call. The spatial mapping is immediately stopped. If the mapping has been enabled, this function will automatically be called by close(). --- # sl::GNSSData **Module:** **Positional Tracking Module** Class containing GNSS data to be used for positional tracking as prior. `#include ` ## Public Functions Documentation ### function GNSSData ```cpp GNSSData() ``` Constructor. ### function setCoordinates ```cpp void setCoordinates( double latitude, double longitude, double altitude, bool in_radian =true ) ``` Sets the sl::LatLng coordinates of sl::GNSSData. **Parameters**: * **latitude** Latitude coordinate. * **longitude** Longitude coordinate. * **altitude** Altitude coordinate. * **in_radian** If the inputs are expressed in radians or in degrees. The sl::LatLng coordinates could be expressed in degrees or radians. ### function getCoordinates ```cpp void getCoordinates( double & latitude, double & longitude, double & altitude, bool in_radian =true ) ``` Gets the sl::LatLng coordinates of the sl::GNSSData. **Parameters**: * **latitude** Latitude coordinate. * **longitude** Longitude coordinate. * **altitude** Altitude coordinate. * **in_radian** Should the output be expressed in radians or degrees. The sl::LatLng coordinates could be expressed in degrees or radians. ## Public Attributes Documentation ### variable ts ```cpp sl::Timestamp ts; ``` Timestamp of the GNSS position (must be aligned with the camera time reference). ### variable position_covariance ```cpp std::array< double, 9 > position_covariance = {0.1 * 0.1, 0, 0, 0, 0.1 * 0.1, 0, 0, 0, 0.1 * 0.1}; ``` 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}`. ### variable longitude_std ```cpp double longitude_std; ``` Longitude standard deviation. ### variable latitude_std ```cpp double latitude_std; ``` Latitude standard deviation. ### variable altitude_std ```cpp double altitude_std; ``` Altitude standard deviation. ### variable gnss_status ```cpp GNSS_STATUS gnss_status = sl::GNSS_STATUS::UNKNOWN; ``` Represents the current status of GNSS. ### variable gnss_mode ```cpp GNSS_MODE gnss_mode = sl::GNSS_MODE::UNKNOWN; ``` Represents the current mode of GNSS. ## Protected Attributes Documentation ### variable longitude ```cpp double longitude; ``` Longitude coordinate. ### variable latitude ```cpp double latitude; ``` Latitude coordinate. ### variable altitude ```cpp double altitude; ``` Altitude coordinate. --- # sl::GeoConverter **Module:** **Fusion Module** Purely static class for Geo functions. `#include ` ## Public Functions Documentation ### function ecef2latlng ```cpp static void ecef2latlng( sl::ECEF & in, sl::LatLng & out ) ``` Convert ECEF coordinates to Lat/Long coordinates. ### function ecef2utm ```cpp static void ecef2utm( sl::ECEF & in, sl::UTM & out ) ``` Convert ECEF coordinates to UTM coordinates. ### function latlng2ecef ```cpp static void latlng2ecef( sl::LatLng & in, sl::ECEF & out ) ``` Convert Lat/Long coordinates to ECEF coordinates. ### function latlng2utm ```cpp static void latlng2utm( sl::LatLng & in, sl::UTM & out ) ``` Convert Lat/Long coordinates to UTM coordinates. ### function utm2ecef ```cpp static void utm2ecef( sl::UTM & in, sl::ECEF & out ) ``` Convert UTM coordinates to ECEF coordinates. ### function utm2latlng ```cpp static void utm2latlng( sl::UTM & in, sl::LatLng & out ) ``` Convert UTM coordinates to Lat/Long coordinates. --- # sl::GeoPose **Module:** **Fusion Module** Holds geographic reference position information. More... `#include ` ## Detailed Description ```cpp class sl::GeoPose; ``` 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. ## Public Functions Documentation ### function GeoPose ```cpp GeoPose() ``` Default constructor. ### function GeoPose ```cpp GeoPose( const GeoPose & geopose ) ``` Copy constructor. **Parameters**: * **geopose** The GeoPose object to copy from. ## Public Attributes Documentation ### variable pose_data ```cpp sl::Transform pose_data; ``` The 4x4 matrix defining the pose in the East-North-Up (ENU) coordinate system. ### variable pose_covariance ```cpp float[36] pose_covariance; ``` The pose covariance matrix in ENU. ### variable horizontal_accuracy ```cpp double horizontal_accuracy; ``` The horizontal accuracy of the pose in meters. ### variable vertical_accuracy ```cpp double vertical_accuracy; ``` The vertical accuracy of the pose in meters. ### variable latlng_coordinates ```cpp sl::LatLng latlng_coordinates; ``` The latitude, longitude, and altitude coordinates of the pose. ### variable heading ```cpp double heading; ``` The heading (orientation) of the pose in radians. 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. ### variable timestamp ```cpp sl::Timestamp timestamp; ``` The timestamp associated with the GeoPose. --- # sl::InputType **Module:** **Video Module** Class defining the input type used in the ZED SDK. More... `#include ` ## Detailed Description ```cpp class sl::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. ## Public Types Documentation ### enum INPUT_TYPE | Enumerator | Value | Description | | ---------- | ----- | ----------- | | 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 enableStreaming() / 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 | Lists input types in the ZED SDK. ## Public Functions Documentation ### function InputType ```cpp InputType() ``` Default constructor. ### function InputType ```cpp InputType( const InputType & input_type ) =default ``` Copy constructor. ### function setFromCameraID ```cpp void setFromCameraID( int id =-1, sl::BUS_TYPE bus_type =sl::BUS_TYPE::AUTO ) ``` Set the input as the camera with specified id. **Parameters**: * **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. * **bus_type** : Whether the camera is a USB or a GMSL camera. **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. ### function setFromSerialNumber ```cpp void setFromSerialNumber( unsigned int camera_serial_number ) ``` Set the input as the camera with specified serial number. **Parameters**: * **camera_serial_number** : Serial number of the camera to open. ### function setFromSerialNumber ```cpp void setFromSerialNumber( sl::String serial_number ) ``` Set the input as the sensor with specified serial number (string version). **Parameters**: * **serial_number** : Serial number of the sensor to open (as a string). For ZED/ZEDOne cameras, the string is parsed to an unsigned int and the standard method is called. For Lidar sensors (which have string-based serial numbers like "991937000508"), the string is used directly for device discovery and matching. ### function setFromGMSLPort ```cpp void setFromGMSLPort( int gmsl_port =-1 ) ``` Set the input as the camera with specified GMSL port. **Parameters**: * **gmsl_port** : GMSL port number of the camera to open. Default: -1. Any number < 0 will try to open the first available GMSL camera. **Note**: Only available on NVIDIA Jetson platforms with GMSL cameras. ### function setFromSVOFile ```cpp void setFromSVOFile( sl::String svo_input_filename ) ``` Set the input as the SVO specified with the filename. **Parameters**: * **svo_input_filename** : Path of the SVO file to open. ### function setFromStream ```cpp void setFromStream( sl::String sender_ip, unsigned short port =30000 ) ``` Set the input as the stream defined by the IP address and the port of the sending device. **Parameters**: * **sender_ip** : IP address of the streaming sender. * **port** : 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. ### function getType ```cpp inline INPUT_TYPE getType() const ``` Returns the current input type. ### function getConfiguration ```cpp inline sl::String getConfiguration() const ``` Returns the current input configuration as a string e.g: SVO name, serial number, streaming ip, etc. ### function isInit ```cpp inline bool isInit() const ``` Check whether the input is set. ### function setVirtualStereoFromCameraIDs ```cpp bool setVirtualStereoFromCameraIDs( int id_left, int id_right, unsigned int virtual_serial_number ) ``` Set the input as the ZED Ones with specified ids for a virtual stereo rig. **Parameters**: * **id_left** : Id of the left ZED One camera to open. * **id_right** : Id of the right ZED One camera to open. * **virtual_serial_number** : Serial number of the virtual stereo rig to load its custom calibration **Return**: error: true if there's an error **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: sl::generateVirtualStereoSerialNumber ### function setVirtualStereoFromSerialNumbers ```cpp bool setVirtualStereoFromSerialNumbers( unsigned int camera_left_serial_number, unsigned int camera_right_serial_number, unsigned int virtual_serial_number ) ``` Set the input as the ZED Ones with specified serial numbers for a virtual stereo rig. **Parameters**: * **camera_left_serial_number** : Serial number of the left ZED One camera to open. * **camera_right_serial_number** : Serial number of the right ZED One camera to open. * **virtual_serial_number** : Serial number of the virtual stereo rig to load its custom calibration **Return**: error: true if there's an error **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: sl::generateVirtualStereoSerialNumber ### function save ```cpp bool save( String filename ) const ``` Saves the current set of parameters into a file to be reloaded with the load() method. **Parameters**: * **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. * In case a file already exists, the method will return false and existing file will not be updated. ### function load ```cpp bool load( String filename ) ``` Loads a set of parameters from the values contained in a previously saved file. **Parameters**: * **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. **Note**: As the InitParameters files can be easily modified manually (using a text editor) this function allows you to test various settings without re-compiling your application. ```cpp InitParameters init_params; // Set initial parameters init_params.load("initParameters.yml"); // Load the init_params from a previously exported file ``` ### function encode ```cpp bool encode( String & serialized_content ) const ``` Generate a JSON Object (with the struct type as a key) containing the serialized struct, converted into a string. **Parameters**: * **serialized_content** output string containing the JSON Object **Return**: True if file was successfully saved, otherwise false. ### function decode ```cpp bool decode( const String & serialized_content ) ``` Fill the structure from the serialized json object contained in the input string. **Parameters**: * **serialized_content** input string containing the JSON Object **Return**: True if the decoding was successful, otherwise false. ### function operator== ```cpp bool operator==( const InputType & param1 ) const ``` Comparison operator ==. **Parameters**: * **param1** to compare **Return**: true if the two struct are identical ### function operator!= ```cpp bool operator!=( const InputType & param1 ) const ``` Comparison operator !=. **Parameters**: * **param1** to compare **Return**: true if the two struct are different --- # sl::KeyFrame **Module:** **Positional Tracking Module** Represents a keyframe in the tracking system. `#include ` ## Public Attributes Documentation ### variable pose ```cpp sl::Transform pose; ``` Position and orientation of the keyframe. ### variable timestamp ```cpp sl::Timestamp timestamp; ``` Timestamp when the keyframe was captured. ### variable is_loaded ```cpp bool is_loaded = false; ``` boolean indicating if the keyframe come from a loaded area file. --- # sl::Landmark **Module:** **Positional Tracking Module** Represents a 3d landmark. `#include ` ## Public Attributes Documentation ### variable id ```cpp uint64_t id; ``` Unique identifier for the landmark. ### variable position ```cpp sl::float3 position; ``` World position of the landmark. --- # sl::Landmark2D **Module:** **Positional Tracking Module** Represents the projection of a 3d landmark in the image. `#include ` ## Public Attributes Documentation ### variable id ```cpp uint64_t id; ``` Unique identifier of the corresponding landmark. ### variable image_position ```cpp sl::uint2 image_position; ``` Projection of the landmark in the image. ### variable dynamic_confidence ```cpp float dynamic_confidence; ``` 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. --- # sl::LatLng **Module:** **Fusion Module** Represents a world position in LatLng format. `#include ` ## Public Functions Documentation ### function getCoordinates ```cpp void getCoordinates( double & latitude, double & longitude, double & altitude, bool in_radian =true ) const ``` Get the coordinates in radians (default) or in degrees. **Parameters**: * **latitude** Latitude coordinate. * **longitude** Longitude coordinate. * **altitude** Altitude coordinate. * **in_radian** Should the output be expressed in radians or degrees. ### function setCoordinates ```cpp void setCoordinates( double latitude, double longitude, double altitude, bool in_radian =true ) ``` Set the coordinates in radians (default) or in degrees. **Parameters**: * **latitude** Latitude coordinate. * **longitude** Longitude coordinate. * **altitude** Altitude coordinate. * **in_radian** Is input are in radians or in degrees. ### function getLatitude ```cpp double getLatitude( bool in_radian =true ) const ``` Get the latitude coordinate. **Parameters**: * **in_radian** Is the output should be in radian or degree. **Return**: Latitude in radian or in degree depending `in_radian` parameter. ### function getLongitude ```cpp double getLongitude( bool in_radian =true ) const ``` Get the longitude coordinate. **Parameters**: * **in_radian** is the output should be in radian or degree. **Return**: Longitude in radian or in degree depending `in_radian` parameter. ### function getAltitude ```cpp double getAltitude() const ``` Get the altitude coordinate. **Return**: Altitude coordinate in meters. ## Protected Attributes Documentation ### variable latitude ```cpp double latitude; ``` Latitude coordinate. ### variable longitude ```cpp double longitude; ``` Longitude coordinate. ### variable altitude ```cpp double altitude; ``` Altitude coordinate. --- # sl::Lidar **Module:** **Lidar Module** Class for Lidar control and data retrieval. It provides methods to initialize the Lidar, retrieve data, and enable positional tracking. Supports both live sensor input and OSF file playback. More... `#include ` ## Detailed Description ```cpp class sl::Lidar; ``` Class for Lidar control and data retrieval. It provides methods to initialize the Lidar, retrieve data, and enable positional tracking. Supports both live sensor input and OSF file playback. **Note**: **Beta:** The Lidar class is currently in beta. Interfaces and behavior may change in future SDK releases. ```cpp // Example usage with live sensor sl::Lidar lidar; sl::InitLidarParameters init_params; init_params.input.setFromStream("192.168.1.50"); lidar.open(init_params); lidar.grab(); sl::Mat point_cloud; lidar.retrieveMeasure(point_cloud, sl::LIDAR_MEASURE::XYZ); lidar.close(); ``` ```cpp // Example usage with OSF file playback (similar to SVO for Camera) sl::Lidar lidar; sl::InitLidarParameters init_params; init_params.input.setFromSVOFile("/path/to/recording.osf"); lidar.open(init_params); while (lidar.grab() == sl::ERROR_CODE::SUCCESS) { sl::Mat point_cloud; lidar.retrieveMeasure(point_cloud, sl::LIDAR_MEASURE::XYZ); // Process point cloud... } lidar.close(); ``` ## Public Functions Documentation ### function Lidar ```cpp Lidar() ``` Lidar constructor. ### function ~Lidar ```cpp ~Lidar() ``` Lidar destructor. ### function open ```cpp sl::ERROR_CODE open( InitLidarParameters params ) ``` Opens the Lidar. **Parameters**: * **params** : The initialization parameters. **Return**: [ERROR_CODE::SUCCESS] if successful, otherwise an error code. ### function isOpened ```cpp bool isOpened() const ``` Checks if the Lidar is opened. **Return**: True if opened, false otherwise. ### function getInitParameters ```cpp InitLidarParameters getInitParameters() const ``` Returns the initialization parameters used to open the Lidar. **Return**: The InitLidarParameters. ### function getLidarInformation ```cpp LidarInformation getLidarInformation() const ``` Returns the Lidar information. **Return**: The LidarInformation containing device info and sensor configuration. ### function getCUDAContext ```cpp CUcontext getCUDAContext() const ``` Returns the CUDA context used by the Lidar when GPU mode is enabled. **Return**: The CUDA context, or nullptr if GPU mode is disabled or not initialized. This method allows you to retrieve the CUDA context created by or provided to the SDK, enabling shared GPU memory operations with other CUDA-enabled libraries. ### function read ```cpp sl::ERROR_CODE read() ``` Reads the next data chunk. **Return**: [ERROR_CODE::SUCCESS] if successful. ### function grab ```cpp sl::ERROR_CODE grab() ``` Grabs a new frame. **Return**: [ERROR_CODE::SUCCESS] if successful. ### function retrieveMeasure ```cpp sl::ERROR_CODE retrieveMeasure( sl::Mat & mat, sl::LIDAR_MEASURE measure, sl::Resolution res =sl::Resolution(0, 0), sl::MEM type =sl::MEM::CPU, sl::VIEW_COLOR_MAP color_map =sl::VIEW_COLOR_MAP::AUTO, cudaStream_t stream =0 ) ``` Retrieves a measure texture (raw float data). **Parameters**: * **mat** : The sl::Mat to store the measure. * **measure** : The type of measure to retrieve. * **res** : The resolution to resize the measure (optional). * **type** : The memory type (CPU or GPU). * **color_map** : The colormap if applicable. * **stream** : The CUDA stream for asynchronous operations (optional, GPU mode only). **Return**: [ERROR_CODE::SUCCESS] if successful. ### function retrieveView ```cpp sl::ERROR_CODE retrieveView( sl::Mat & mat, sl::LIDAR_VIEW view, sl::Resolution res =sl::Resolution(0, 0), sl::VIEW_COLOR_MAP color_map =sl::VIEW_COLOR_MAP::AUTO, cudaStream_t stream =0 ) ``` Retrieves a view texture (visual data). **Parameters**: * **mat** : The sl::Mat to store the view. * **view** : The type of view to retrieve. * **res** : The resolution to resize the view (optional). * **color_map** : The colormap to use. * **stream** : The CUDA stream for asynchronous operations (optional, GPU mode only). **Return**: [ERROR_CODE::SUCCESS] if successful. ### function getTimestamp ```cpp sl::Timestamp getTimestamp( sl::TIME_REFERENCE reference_time ) const ``` Returns the timestamp of the frame or the current time. **Parameters**: * **reference_time** : The selected TIME_REFERENCE. - [TIME_REFERENCE::IMAGE] : timestamp of the last grabbed frame. - [TIME_REFERENCE::CURRENT] : current system time. **Return**: The timestamp in nanoseconds. 0 if not available. **Note**: As this function returns UNIX timestamps, the reference it uses is common across several Lidar instances. This function can also be used when playing back an OSF file. ```cpp sl::Timestamp last_frame_timestamp = lidar.getTimestamp(sl::TIME_REFERENCE::IMAGE); sl::Timestamp current_timestamp = lidar.getTimestamp(sl::TIME_REFERENCE::CURRENT); std::cout << "Latest frame timestamp: " << last_frame_timestamp << "ns from Epoch." << std::endl; std::cout << "Current timestamp: " << current_timestamp << "ns from Epoch." << std::endl; ``` ### function getCurrentFPS ```cpp float getCurrentFPS() const ``` Returns the current framerate at which the grab() method is successfully called. **Return**: The current SDK framerate. **Warning**: The returned framerate (number of frames grabbed per second) can be lower than the Lidar mode fps if the grab() function runs slower than the data stream or is called too often. The returned value is based on the difference of timestamps between two successful grab() calls. ```cpp float current_fps = lidar.getCurrentFPS(); std::cout << "Current framerate: " << current_fps << std::endl; ``` ### function getSensorsData ```cpp sl::ERROR_CODE getSensorsData( sl::SensorsData & data, sl::TIME_REFERENCE reference_time =sl::TIME_REFERENCE::CURRENT ) ``` Retrieves sensors data (IMU). **Parameters**: * **data** : The SensorsData object to store the data. * **reference_time** : The reference time for the data. **Return**: [ERROR_CODE::SUCCESS] if successful. ### function enablePositionalTracking ```cpp sl::ERROR_CODE enablePositionalTracking( PositionalTrackingLidarParameters params =PositionalTrackingLidarParameters() ) ``` Enables positional tracking. **Parameters**: * **params** : The positional tracking parameters (optional). **Return**: [ERROR_CODE::SUCCESS] if successful. ### function disablePositionalTracking ```cpp void disablePositionalTracking() ``` Disables positional tracking. ### function getPosition ```cpp sl::POSITIONAL_TRACKING_STATE getPosition( sl::Pose & pose, sl::REFERENCE_FRAME reference_frame =sl::REFERENCE_FRAME::WORLD ) ``` Retrieves the current position. **Parameters**: * **pose** : The Pose object to store the position. * **reference_frame** : The reference frame for the position. **Return**: POSITIONAL_TRACKING_STATE. ### function enableRecording ```cpp sl::ERROR_CODE enableRecording( RecordingLidarParameters params ) ``` Enables recording. **Parameters**: * **params** : The recording parameters. **Return**: [ERROR_CODE::SUCCESS] if successful. ### function disableRecording ```cpp void disableRecording() ``` Disables recording. ### function getSVOPosition ```cpp int getSVOPosition() const ``` Gets the current SVO/OSF playback position (frame index). **Return**: The current frame index, or -1 if not in playback mode. ### function setSVOPosition ```cpp sl::ERROR_CODE setSVOPosition( int frame_number ) ``` Sets the SVO/OSF playback position (frame index). **Parameters**: * **frame_number** : The frame index to seek to. **Return**: [ERROR_CODE::SUCCESS] if successful. ### function getSVONumberOfFrames ```cpp int getSVONumberOfFrames() const ``` Gets the total number of frames in the SVO/OSF file. **Return**: The total number of frames, or -1 if not in playback mode. ### function getSVOPositionAtTimestamp ```cpp int getSVOPositionAtTimestamp( sl::Timestamp timestamp ) const ``` Retrieves the frame index within the SVO/OSF file corresponding to the provided timestamp. **Parameters**: * **timestamp** : The timestamp to search for (in nanoseconds). **Return**: The frame index closest to the given timestamp, or -1 if not in playback mode. ### function setTimestampBaseOffset ```cpp void setTimestampBaseOffset( int64_t offset ) ``` Sets the base timestamp offset for converting OSF sensor timestamps to Unix epoch. **Parameters**: * **offset** : The offset in nanoseconds to add to OSF timestamps. **Note**: This should be called after open() and before reading frames. OSF files store sensor-relative timestamps (nanoseconds since sensor boot). This method sets an offset that is added to OSF timestamps when returning frame timestamps via getTimestamp(IMAGE), and subtracted when seeking via getSVOPositionAtTimestamp(). This is used by Sensors::syncSVO() to align LiDAR timestamps with camera timestamps for multi-sensor synchronized playback. ### function getTimestampBaseOffset ```cpp int64_t getTimestampBaseOffset() const ``` Gets the base timestamp offset for OSF playback. **Return**: The current timestamp offset in nanoseconds. ### function pauseSVOReading ```cpp void pauseSVOReading( bool status ) ``` Pauses or resumes SVO/OSF reading. **Parameters**: * **status** : If true, the reading is paused. If false, the reading is resumed. **Note**: This is only relevant when InitLidarParameters::svo_real_time_mode is enabled. ### function close ```cpp void close() ``` Closes the Lidar. ### function getDeviceList ```cpp static std::vector< LidarDeviceProperties > getDeviceList() ``` Returns a list of available Lidar devices. **Return**: A vector of LidarDeviceProperties. ### function getStreamingDeviceList ```cpp static std::vector< LidarDeviceProperties > getStreamingDeviceList() ``` Returns a list of streaming Lidar devices. **Return**: A vector of LidarDeviceProperties. --- # sl::Matrix3f **Module:** **Core Module** Class representing a generic 3*3 matrix. More... `#include ` Inherited by Rotation ## Detailed Description ```cpp class sl::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' ptr or by element attribute. | | | | |--—|--—|--—| | r00 | r01 | r02 | | r10 | r11 | r12 | | r20 | r21 | r22 | ## Public Functions Documentation ### function Matrix3f ```cpp Matrix3f() ``` Default constructor. ### function Matrix3f ```cpp Matrix3f( float data[] ) ``` Copy constructor (deep copy). ### function Matrix3f ```cpp Matrix3f( const Matrix3f & mat ) ``` Cpy constructor (deep copy). **Parameters**: * **mat** : sl::Matrix3f to copy. ### function Matrix3f ```cpp Matrix3f( Matrix3f && mat ) ``` Move constructor. **Parameters**: * **mat** : sl::Matrix3f to move. ### function operator= ```cpp Matrix3f & operator=( const Matrix3f & mat ) ``` Copy assignment operator. ### function operator= ```cpp Matrix3f & operator=( Matrix3f && mat ) ``` Move assignment operator. ### function operator* ```cpp Matrix3f operator*( const Matrix3f & mat ) const ``` Gives the result of the multiplication between two sl::Matrix3f. ### function operator* ```cpp Matrix3f operator*( const float & scalar ) const ``` Gives the result of the multiplication between a sl::Matrix3f and a scalar. ### function operator+ ```cpp Matrix3f operator+( const Matrix3f & mat ) const ``` Gives the result of the addition between two sl::Matrix3f. ### function operator+ ```cpp Matrix3f operator+( const float & scalar ) const ``` Gives the result of the addition between a sl::Matrix3f and a scalar. ### function operator- ```cpp Matrix3f operator-( const Matrix3f & mat ) const ``` Gives the result of the subtraction between two sl::Matrix3f. ### function operator- ```cpp Matrix3f operator-( const float & scalar ) const ``` Gives the result of the subtraction between a sl::Matrix3f and a scalar. ### function operator== ```cpp bool operator==( const Matrix3f & mat ) const ``` Test two sl::Matrix3f equality. ### function operator!= ```cpp bool operator!=( const Matrix3f & mat ) const ``` Test two sl::Matrix3f inequality. ### function operator() ```cpp float & operator()( int u, int v ) ``` Gets access to a specific point in the sl::Matrix3f (read/write). **Parameters**: * **u** : Row to get the value from. * **v** : Column to get the value from. **Return**: The value at the u, v coordinates. ### function inverse ```cpp void inverse() ``` Sets the sl::Matrix3f to its inverse. ### function transpose ```cpp void transpose() ``` Sets the sl::Matrix3f to its transpose. ### function setIdentity ```cpp void setIdentity() ``` Sets the sl::Matrix3f to identity. ### function setZeros ```cpp void setZeros() ``` Sets the sl::Matrix3f to zero. ### function getInfos ```cpp String getInfos() const ``` Returns the components of the sl::Matrix3f in a sl::String. **Return**: A sl::String containing the components of the current sl::Matrix3f. ### function inverse ```cpp static Matrix3f inverse( const Matrix3f & rotation ) ``` Returns the inverse of a sl::Matrix3f. **Parameters**: * **rotation** : sl::Matrix3f to compute the inverse from. **Return**: The inverse of the sl::Matrix3f given as input. ### function transpose ```cpp static Matrix3f transpose( const Matrix3f & rotation ) ``` Returns the transpose of a sl::Matrix3f. **Parameters**: * **rotation** : sl::Matrix3f to compute the transpose from. **Return**: The transpose of the sl::Matrix3f given as input. ### function identity ```cpp static Matrix3f identity() ``` Creates an identity sl::Matrix3f. **Return**: A sl::Matrix3f set to identity. ### function zeros ```cpp static Matrix3f zeros() ``` Creates a sl::Matrix3f filled with zeros. **Return**: A sl::Matrix3f filled with zeros. ## Public Attributes Documentation ### variable matrix_name ```cpp String matrix_name; ``` Name of the matrix (optional). --- # sl::Matrix4f **Module:** **Core Module** Class representing a generic 4*4 matrix. More... `#include ` Inherited by Transform ## Detailed Description ```cpp class sl::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 'm' ptr or by element attribute. | | | | | |-|-|-|-| | r00 | r01 | r02 | tx | | r10 | r11 | r12 | ty | | r20 | r21 | r22 | tz | | m30 | m31 | m32 | m33 | ## Public Functions Documentation ### function Matrix4f ```cpp Matrix4f() ``` Default constructor. ### function ~Matrix4f ```cpp virtual ~Matrix4f() =default ``` ### function Matrix4f ```cpp Matrix4f( float data[] ) ``` Copy constructor (deep copy). ### function Matrix4f ```cpp Matrix4f( const Matrix4f & mat ) ``` Copy constructor (deep copy). **Parameters**: * **mat** : sl::Matrix3f to copy. ### function Matrix4f ```cpp Matrix4f( Matrix4f && mat ) ``` Move constructor. **Parameters**: * **mat** : sl::Matrix4f to move. ### function operator* ```cpp Matrix4f operator*( const Matrix4f & mat ) const ``` Gives the result of the multiplication between two sl::Matrix4f. ### function operator* ```cpp Matrix4f operator*( const Vector4< float > & vect ) const ``` Gives the result of the multiplication between a sl::Matrix4f and a sl::float4. ### function operator* ```cpp Matrix4f operator*( const float & scalar ) const ``` Gives the result of the multiplication between a sl::Matrix4f and a scalar. ### function operator+ ```cpp Matrix4f operator+( const Matrix4f & mat ) const ``` Gives the result of the addition between two sl::Matrix4f. ### function operator+ ```cpp Matrix4f operator+( const float & scalar ) const ``` Gives the result of the addition between a sl::Matrix4f and a scalar. ### function operator- ```cpp Matrix4f operator-( const Matrix4f & mat ) const ``` Gives the result of the subtraction between two sl::Matrix4f. ### function operator- ```cpp Matrix4f operator-( const float & scalar ) const ``` Gives the result of the subtraction between a sl::Matrix4f and a scalar. ### function operator== ```cpp bool operator==( const Matrix4f & mat ) const ``` Tests two sl::Matrix4f equality. ### function operator!= ```cpp bool operator!=( const Matrix4f & mat ) const ``` Tests two sl::Matrix4f inequality. ### function operator() ```cpp float & operator()( int const u, int const v ) ``` Gets access to a specific point in the sl::Matrix4f (read/write). **Parameters**: * **u** : Row to get the value from. * **v** : Column to get the value from. **Return**: The value at the u, v coordinates. ### function operator() ```cpp float operator()( int const u, int const v ) const ``` Gets access to a specific point in the sl::Matrix4f (read). **Parameters**: * **u** : Row to get the value from. * **v** : Column to get the value from. **Return**: The value at the u, v coordinates. ### function inverse ```cpp ERROR_CODE inverse() ``` 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). ### function transpose ```cpp void transpose() ``` Sets the sl::Matrix4f to its transpose. ### function setIdentity ```cpp void setIdentity() ``` Sets the sl::Matrix4f to identity. ### function setZeros ```cpp void setZeros() ``` Sets the sl::Matrix4f to zero. ### function setSubMatrix3f ```cpp ERROR_CODE setSubMatrix3f( Matrix3f input, int row =0, int column =0 ) ``` Sets a sl::Matrix3f inside the sl::Matrix4f. **Parameters**: * **input** : Sub-matrix to put inside the sl::Matrix4f. * **row** : Index of the row to start the 3x3 block. Must be 0 or 1. * **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. **Note**: Can be used to set the rotation matrix when the sl::Matrix4f is a pose or an isometric matrix. ### function setSubVector3f ```cpp ERROR_CODE setSubVector3f( Vector3< float > input, int column =3 ) ``` Sets a sl::Vector3 inside the sl::Matrix4f at the specified column index. **Parameters**: * **input** : Sub-vector to put inside the sl::Matrix4f. * **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. **Note**: Can be used to set the translation/position matrix when the sl::Matrix4f is a pose or an isometry. ### function setSubVector4f ```cpp ERROR_CODE setSubVector4f( Vector4< float > input, int column =3 ) ``` Sets a sl::Vector4 inside the sl::Matrix4f at the specified column index. **Parameters**: * **input** : Sub-vector to put inside the sl::Matrix4f. * **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. **Note**: Can be used to set the translation/position matrix when the sl::Matrix4f is a pose or an isometry. ### function operator= ```cpp Matrix4f & operator=( const Matrix4f & mat ) ``` Copy assignment operator. ### function operator= ```cpp Matrix4f & operator=( Matrix4f && mat ) ``` Move assignment operator. ### function getInfos ```cpp String getInfos() const ``` Returns the components of the sl::Matrix4f in a sl::String. **Return**: A sl::String containing the components of the current sl::Matrix4f. ### function inverse ```cpp static Matrix4f inverse( const Matrix4f & mat ) ``` Creates the inverse of a sl::Matrix4f. **Parameters**: * **mat** : sl::Matrix4f to compute the inverse from. **Return**: The inverse of the sl::Matrix4f given as input. ### function transpose ```cpp static Matrix4f transpose( const Matrix4f & mat ) ``` Creates the transpose of a sl::Matrix4f. **Parameters**: * **mat** : sl::Matrix4f to compute the transpose from. **Return**: The transpose of the sl::Matrix4f given as input. ### function identity ```cpp static Matrix4f identity() ``` Creates an identity sl::Matrix4f. **Return**: A sl::Matrix4f set to identity. ### function zeros ```cpp static Matrix4f zeros() ``` Creates a sl::Matrix4f filled with zeros. **Return**: A sl::Matrix4f filled with zero. ## Public Attributes Documentation ### variable matrix_name ```cpp String matrix_name; ``` Name of the matrix (optional). --- # sl::Mesh **Module:** **Spatial Mapping Module** Class representing a mesh and containing the geometric (and optionally texture) data of the scene captured by the spatial mapping module. More... `#include ` ## Detailed Description ```cpp class sl::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. ## Public Types Documentation ### typedef chunkList ```cpp typedef std::vector chunkList; ``` Vector of chunks id. ## Public Functions Documentation ### function Mesh ```cpp Mesh() ``` Default constructor. Creates an empty sl::Mesh. ### function ~Mesh ```cpp ~Mesh() ``` Default destructor. ### function operator[] ```cpp Chunk & operator[]( int index ) ``` Defines the [] operator to directly access the desired chunk. ### function getNumberOfTriangles ```cpp size_t getNumberOfTriangles() ``` Computes the total number of triangles stored in all chunks. **Return**: The number of triangles stored in all chunks. ### function updateMeshFromChunkList ```cpp void updateMeshFromChunkList( chunkList IDs =chunkList() ) ``` Updates vertices / normals / triangles / uv from chunk data pointed by the given sl::Mesh::chunkList. **Parameters**: * **IDs** : Indices of chunks which will be concatenated. Default: (empty). **Note**: If the given sl::Mesh::chunkList is empty, all chunks will be used to update the current sl::Mesh. ### function getVisibleList ```cpp chunkList getVisibleList( Transform camera_pose ) ``` Computes the sl::Mesh::chunkList of visible chunks from a specific point of view. **Parameters**: * **camera_pose** : Point of view (given in the same reference as the vertices). **Return**: The list of id of visible chunks. ### function getSurroundingList ```cpp chunkList getSurroundingList( Transform camera_pose, float radius ) ``` Computes the sl::Mesh::chunkList of chunks close to a specific point of view. **Parameters**: * **camera_pose** : Point of view (given in the same reference as the vertices). * **radius** : Radius determining closeness (given in the same unit as the mesh). **Return**: The list of id of chunks close to the given point. ### function filter ```cpp bool filter( MeshFilterParameters mesh_filter_params =MeshFilterParameters(), bool update_chunk_only =false ) ``` Filters the mesh. **Parameters**: * **mesh_filter_params** : Filtering parameters. Default: a preset of sl::MeshFilterParameters. * **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. * It is not recommended to call it every time you retrieve a mesh but only at the end of your spatial mapping process. The resulting mesh is smoothed, small holes are filled, and small blobs of non-connected triangles are deleted. ### function applyTexture ```cpp bool applyTexture( MESH_TEXTURE_FORMAT texture_format =MESH_TEXTURE_FORMAT::RGB ) ``` Applies a texture to the mesh. **Parameters**: * **texture_format** : Number of channels desired for the computed texture. Default: [[sl::MESH_TEXTURE_FORMAT::RGB]](MESH_TEXTURE_FORMAT). **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). * This method can require a lot of computation time depending on the number of triangles in the mesh. * 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. * The mesh should be filtered before calling this method since filter() will erase the textures. * The texturing is also significantly slower on non-filtered meshes. 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. Vectors of vertices / normals and uv have now the same size. ### function mergeChunks ```cpp void mergeChunks( int faces_per_chunk ) ``` Merges current chunks. **Parameters**: * **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. This method can be used to merge chunks into bigger sets to improve rendering process. ### function getGravityEstimate ```cpp sl::float3 getGravityEstimate() ``` Estimates the gravity vector. **Return**: The estimated gravity vector. **Note**: This can be used to find the gravity to create realistic physical interactions. This method looks for a dominant plane in the whole mesh considering that it is the floor (or a horizontal plane). ### function getBoundaries ```cpp std::vector< int > getBoundaries() ``` Compute the indices of boundary vertices. **Return**: The indices of boundary vertices. ### function save ```cpp bool save( String filename, MESH_FILE_FORMAT type =MESH_FILE_FORMAT::OBJ, chunkList IDs =chunkList() ) ``` Saves the current sl::Mesh into a file. **Parameters**: * **filename** : Path of the file to store the mesh in. * **type** : File extension type. Default: sl::MESH_FILE_FORMAT::OBJ. * **IDs** : 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 support textures data. * This method operates on the sl.Mesh not on chunks. * This way you can save different parts of your sl.Mesh by updating it with updateMeshFromChunkList(). ### function load ```cpp bool load( String filename, bool update_chunk_only =false ) ``` Loads the mesh from a file. **Parameters**: * **filename** : Path of the file to load the mesh from. * **update_chunk_only** : 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. ### function clear ```cpp void clear() ``` Clears all the data. ## Public Attributes Documentation ### variable chunks ```cpp std::vector< Chunk > chunks; ``` Vector of chunks constituting the sl::Mesh. ### variable vertices ```cpp std::vector< float3 > vertices; ``` Vector of vertices. Vertices are defined by a 3D point `{x, y, z}`. ### variable triangles ```cpp std::vector< uint3 > triangles; ``` Vector of triangles/faces. Triangles are defined as a set of three vertices indexes `{v1, v2, v3}`. ### variable normals ```cpp std::vector< float3 > normals; ``` Vector of normals. **Note**: A normal is defined for each vertex. Normals are defined by three components `{nx, ny, nz}`. ### variable colors ```cpp std::vector< uchar3 > colors; ``` Vector of colors. **Note**: A color is defined for each vertex. Colors are defined by three components `{b, g, r}`. ### variable uv ```cpp std::vector< float2 > uv; ``` UVs defines the 2D projection of each vertices onto the texture. **Note**: Contains data only if your mesh has textures (by loading it or calling sl::Mesh.applyTexture()). 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. ### variable texture ```cpp Mat texture; ``` Texture of the sl::Mesh. **Note**: Contains data only if your mesh has textures (by loading it or calling sl::Mesh.applyTexture()). --- # sl::MeshFilterParameters **Module:** **Spatial Mapping Module** Class containing a set of parameters for the mesh filtration functionality. More... `#include ` ## Detailed Description ```cpp class sl::MeshFilterParameters; ``` Class containing a set of parameters for the mesh filtration functionality. **Note**: Parameters can be adjusted by the user. The default constructor sets all parameters to their default settings. ## Public Types Documentation ### enum MESH_FILTER | Enumerator | Value | Description | | ---------- | ----- | ----------- | | 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. | Lists available mesh filtering intensities. ## Public Functions Documentation ### function MeshFilterParameters ```cpp inline MeshFilterParameters( MESH_FILTER mesh_filtering =MESH_FILTER::LOW ) ``` Default constructor. All the parameters are set to their default values. ### function set ```cpp inline void set( MESH_FILTER mesh_filtering =MESH_FILTER::LOW ) ``` Sets the filtering intensity. **Parameters**: * **mesh_filtering** : Desired sl::MeshFilterParameters::MESH_FILTER. ## Public Attributes Documentation ### variable filtering ```cpp MESH_FILTER filtering = MESH_FILTER::LOW; ``` Filtering intensity. --- # sl::ObjectData **Module:** **Object Detection Module** Class containing data of a detected object such as its bounding_box, label, id and its 3D position. `#include ` ## Public Functions Documentation ### function ObjectData ```cpp ObjectData() ``` Default constructor. ### function ~ObjectData ```cpp ~ObjectData() ``` Default destructor. ## Public Attributes Documentation ### variable id ```cpp int id; ``` Object identification number. **Note**: * Only available if sl::ObjectDetectionParameters.enable_tracking is activated. * Otherwise, it will be set to -1. It is used as a reference when tracking the object through the frames. ### variable unique_object_id ```cpp String unique_object_id; ``` Unique id to help identify and track AI detections. It can be either generated externally, or by using generate_unique_id() or left empty. ### variable raw_label ```cpp int raw_label = 0; ``` Object raw label. It is forwarded from sl::CustomBoxObjectData when using [[sl::OBJECT_DETECTION_MODEL::CUSTOM_BOX_OBJECTS]](OBJECT_DETECTION_MODEL). ### variable label ```cpp OBJECT_CLASS label; ``` Object class/category to identify the object type. ### variable sublabel ```cpp OBJECT_SUBCLASS sublabel; ``` Object sub-class/sub-category to identify the object type. ### variable tracking_state ```cpp OBJECT_TRACKING_STATE tracking_state; ``` Object tracking state. ### variable action_state ```cpp OBJECT_ACTION_STATE action_state; ``` Object action state. ### variable position ```cpp sl::float3 position; ``` Object 3D centroid. **Note**: It is defined in sl::InitParameters.coordinate_units and expressed in sl::RuntimeParameters.measure3D_reference_frame. ### variable velocity ```cpp sl::float3 velocity; ``` Object 3D velocity. **Note**: It is defined in `sl::InitParameters.coordinate_units / s` and expressed in sl::RuntimeParameters.measure3D_reference_frame. ### variable position_covariance ```cpp float[6] position_covariance; ``` Covariance matrix of the 3D position. **Note**: It is represented by its upper triangular matrix value ```cpp = [p0, p1, p2] [p1, p3, p4] [p2, p4, p5] ``` where pi is `position_covariance[i]` ### variable bounding_box_2d ```cpp std::vector< sl::uint2 > bounding_box_2d; ``` 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. ```cpp A ------ B | Object | D ------ C ``` ### variable mask ```cpp sl::Mat mask; ``` 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]](OBJECT_TRACKING_STATE)) that have a valid depth. * Otherwise, the mask will not be initialized (`mask.isInit() == false`). ### variable confidence ```cpp float confidence; ``` 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. ### variable bounding_box ```cpp std::vector< sl::float3 > bounding_box; ``` 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. ```cpp 1 ------ 2 / /| 0 ------ 3 | | Object | 6 | |/ 4 ------ 7 ``` ### variable dimensions ```cpp sl::float3 dimensions; ``` 3D object dimensions: width, height, length. **Note**: It is defined in sl::InitParameters.coordinate_units and expressed in sl::RuntimeParameters.measure3D_reference_frame. ### variable head_bounding_box_2d ```cpp std::vector< sl::uint2 > head_bounding_box_2d; ``` 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. ### variable head_bounding_box ```cpp std::vector< sl::float3 > head_bounding_box; ``` 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. ### variable head_position ```cpp sl::float3 head_position; ``` 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. --- # sl::Objects **Module:** **Object Detection Module** Class containing the results of the object detection module. More... `#include ` ## Detailed Description ```cpp class sl::Objects; ``` Class containing the results of the object detection module. The detected objects are listed in object_list. ## Public Functions Documentation ### function getObjectDataFromId ```cpp bool getObjectDataFromId( sl::ObjectData & objectData, int objectDataId ) ``` Method that looks for a given object id in the current objects list. **Parameters**: * **objectData** : sl::ObjectData to fill if the search succeeded. * **objectDataId** : Id of the sl::ObjectData to search. **Return**: True if found, otherwise false. ## Public Attributes Documentation ### variable timestamp ```cpp sl::Timestamp timestamp; ``` Timestamp corresponding to the frame acquisition. This value is especially useful for the async mode to synchronize the data. ### variable object_list ```cpp std::vector< sl::ObjectData > object_list; ``` Vector of detected objects. ### variable is_new ```cpp bool is_new = false; ``` Whether object_list has already been retrieved or not. ### variable is_tracked ```cpp bool is_tracked = false; ``` Whether both the object tracking and the world orientation has been setup. ### variable fused_objects_group_name ```cpp sl::String fused_objects_group_name; ``` 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. --- # sl::ObjectsBatch **Module:** **Object Detection Module** Class containing batched data of a detected objects from the object detection module. More... `#include ` ## Detailed Description ```cpp class sl::ObjectsBatch; ``` Class containing batched data of a detected objects from the object detection module. This class can be used to store trajectories. ## Public Attributes Documentation ### variable id ```cpp int id; ``` Id of the batch. ### variable label ```cpp OBJECT_CLASS label; ``` Objects class/category to identify the object type. ### variable sublabel ```cpp OBJECT_SUBCLASS sublabel; ``` Objects sub-class/sub-category to identify the object type. ### variable tracking_state ```cpp OBJECT_TRACKING_STATE tracking_state; ``` Objects tracking state. ### variable positions ```cpp std::vector< sl::float3 > positions; ``` Vector of positions for each object. ### variable position_covariances ```cpp std::vector< std::array< float, 6 > > position_covariances; ``` Vector of positions' covariances for each object. ### variable velocities ```cpp std::vector< sl::float3 > velocities; ``` Vector of 3D velocities for each object. ### variable timestamps ```cpp std::vector< sl::Timestamp > timestamps; ``` Vector of timestamps for each object. ### variable bounding_boxes ```cpp std::vector< std::vector< sl::float3 > > bounding_boxes; ``` Vector of 3D bounding boxes for each object. **Note**: They are defined in sl::InitParameters.coordinate_units and expressed in sl::RuntimeParameters.measure3D_reference_frame. ```cpp 1 ------ 2 / /| 0 ------ 3 | | Object | 6 | |/ 4 ------ 7 ``` ### variable bounding_boxes_2d ```cpp std::vector< std::vector< sl::uint2 > > bounding_boxes_2d; ``` Vector of 2D bounding boxes for each object. **Note**: Expressed in pixels on the original image resolution, `[0, 0]` is the top left corner. ```cpp A ------ B | Object | D ------ C ``` ### variable confidences ```cpp std::vector< float > confidences; ``` Vector of confidences for each object. ### variable action_states ```cpp std::vector< OBJECT_ACTION_STATE > action_states; ``` Vector of action states for each object. ### variable head_bounding_boxes_2d ```cpp std::vector< std::vector< sl::uint2 > > head_bounding_boxes_2d; ``` Vector 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. ### variable head_bounding_boxes ```cpp std::vector< std::vector< sl::float3 > > head_bounding_boxes; ``` Vector 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. ### variable head_positions ```cpp std::vector< sl::float3 > head_positions; ``` Vector 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. --- # sl::Orientation **Module:** **Positional Tracking Module** Class representing an orientation/quaternion for the positional tracking module. More... `#include ` Inherits from Vector4< float > ## Additional inherited members **Public Functions inherited from Vector4< float >** | | Name | | -------------- | -------------- | | _FCT_CPU_GPU_ | **Vector4**()
Default constructor. | | _FCT_CPU_GPU_ | **Vector4**(const T & t)
Constructor. | | _FCT_CPU_GPU_ | **Vector4**(const T * tp)
Constructor. | | _FCT_CPU_GPU_ | **Vector4**(const T v0, const T v1, const T v2, const T v3)
Constructor. | | _FCT_CPU_GPU_ | **Vector4**(const Vector4< T > & vec)
Copy constructor. | | _FCT_CPU_GPU_ | **Vector4**(const Vector4< T > & vec, const T d)
Constructor. | | _FCT_CPU_GPU_ | **Vector4**(const Vector3< T > & vec, const T d =0)
Constructor. | | _FCT_CPU_GPU_ Vector4< T > & | **operator=**(const Vector3< T > & other)
Test the equality of the first three components of the sl::Vector4 with a sl::Vector3. | **Friends inherited from Vector4< float >** | | Name | | -------------- | -------------- | | _FCT_CPU_GPU_ friend Vector4< T > & | **operator+=**(Vector4< T > & itself, T d) | | _FCT_CPU_GPU_ friend Vector4< T > & | **operator+=**(Vector4< T > & itself, const Vector4< T > & b) | | _FCT_CPU_GPU_ friend Vector4< T > & | **operator-=**(Vector4< T > & itself, T d) | | _FCT_CPU_GPU_ friend Vector4< T > & | **operator-=**(Vector4< T > & itself, const Vector4< T > & b) | | _FCT_CPU_GPU_ friend Vector4< T > & | **operator*=**(Vector4< T > & itself, T d) | | _FCT_CPU_GPU_ friend Vector4< T > & | **operator*=**(Vector4< T > & itself, const Vector4< T > & b) | | _FCT_CPU_GPU_ friend Vector4< T > & | **operator*=**(Vector4< T > & itself, const Matrix4f & b) | | _FCT_CPU_GPU_ friend Vector4< T > & | **operator/=**(Vector4< T > & itself, T d) | | _FCT_CPU_GPU_ friend Vector4< T > & | **operator/=**(Vector4< T > & itself, const Vector4< T > & b) | | _FCT_CPU_GPU_ friend bool | **operator==**(const Vector4< T > & itself, const Vector4< T > & b) | | _FCT_CPU_GPU_ friend Vector4< T > | **operator-**(const Vector4< T > & b) | | _FCT_CPU_GPU_ friend Vector4< T > | **operator+**(const Vector4< T > & a, const Vector4< T > & b) | | _FCT_CPU_GPU_ friend Vector4< T > | **operator-**(const Vector4< T > & a, const Vector4< T > & b) | | _FCT_CPU_GPU_ friend Vector4< T > | **operator/**(const Vector4< T > & a, T b) | | _FCT_CPU_GPU_ friend Vector4< T > | **operator/**(const Vector4< T > & a, const Vector4< T > & b) | ## Detailed Description ```cpp class sl::Orientation; ``` Class representing an orientation/quaternion for the positional tracking module. sl::Orientation is a vector defined as `[ox, oy, oz, ow]`. ## Public Functions Documentation ### function Orientation ```cpp Orientation() ``` Default constructor. Creates an identity orientation. ### function Orientation ```cpp Orientation( const Orientation & orientation ) ``` Copy constructor (deep copy). **Parameters**: * **orientation** : sl::Orientation to copy. ### function Orientation ```cpp Orientation( const float4 & in ) ``` Copy constructor (deep copy). **Parameters**: * **in** : sl::float4 to copy. ### function Orientation ```cpp Orientation( const Rotation & rotation ) ``` Constructor from an sl::Rotation. **Parameters**: * **rotation** : sl::Rotation to be used. It converts the sl::Rotation representation to the sl::Orientation one. ### function Orientation ```cpp Orientation( const Translation & tr1, const Translation & tr2 ) ``` Constructor from a vector represented by two sl::Translation. **Parameters**: * **tr1** : First point of the vector. * **tr2** : Second point of the vector. ### function operator() ```cpp float operator()( int x ) ``` Gets the value at specific position in the sl::Orientation. **Parameters**: * **x** : Position of the value. **Return**: Value at the x position. ### function operator* ```cpp Orientation operator*( const Orientation & orientation ) const ``` Multiplication operator by an sl::Orientation. **Parameters**: * **orientation** : sl.Orientation to multiply the current one with. **Return**: The result of the multiplication between current sl.Orientation and the one given as input. ### function setRotationMatrix ```cpp void setRotationMatrix( const Rotation & rotation ) ``` Sets the sl::Orientation from an sl::Rotation. **Parameters**: * **rotation** : sl::Rotation to be used. ### function getRotationMatrix ```cpp Rotation getRotationMatrix() const ``` Returns the current sl::Orientation as an sl::Rotation. **Return**: The rotation computed from the orientation data. ### function setIdentity ```cpp void setIdentity() ``` Sets the current sl::Orientation to identity. ### function setZeros ```cpp void setZeros() ``` Fills the current sl::Orientation with zeros. ### function normalise ```cpp void normalise() ``` Normalizes the current sl::Orientation. ### function size ```cpp inline _FCT_CPU_GPU_ int size() const ``` Return the size of the sl::Vector4. **Return**: 4 ### function ptr ```cpp inline _FCT_CPU_GPU_ const float * ptr() const ``` Returns a pointer of the first component. ### function setValues ```cpp inline _FCT_CPU_GPU_ Vector4< float > & setValues( const float * vals ) ``` Sets the components of the sl::Vector1 to the values of the argument. ### function operator[] ```cpp inline _FCT_CPU_GPU_ float & operator[]( const unsigned int i ) ``` Returns the **i-th** component. ### function operator[] ```cpp inline _FCT_CPU_GPU_ const float & operator[]( const unsigned int i ) const ``` Returns the **i-th** component. ### function operator[] ```cpp _FCT_CPU_GPU_ void operator[]( const unsigned int i ) =delete ``` Prevent operator from being called by temporaries (such as rvalue) ### function norm ```cpp inline _FCT_CPU_GPU_ float norm() ``` Returns the norm of the sl::Vector4. ### function square ```cpp inline _FCT_CPU_GPU_ float square() ``` Returns the squared norm of the sl::Vector4. ### function sum ```cpp inline _FCT_CPU_GPU_ float sum() ``` Returns the sum of the components of the sl::Vector4. ### function identity ```cpp static Orientation identity() ``` Creates an sl::Orientation initialized to identity. **Return**: Identity sl::Orientation. ### function zeros ```cpp static Orientation zeros() ``` Creates an sl::Orientation filled with zeros. **Return**: sl::Orientation filled with zeros. ### function normalise ```cpp static Orientation normalise( const Orientation & orient ) ``` Gets the normalized sl::Orientation of a given sl::Orientation. **Parameters**: * **orient** : sl::Orientation to be get the normalized orientation from. **Return**: Another sl::Orientation object equal to normalise. ### function dot ```cpp static inline _FCT_CPU_GPU_ float dot( const Vector4< float > & a, const Vector4< float > & b ) ``` Returns the dot product of two sl::Vector4. ### function distance ```cpp static inline _FCT_CPU_GPU_ float distance( const Vector4< float > & a, const Vector4< float > & b ) ``` Returns the distance between two sl::Vector4. --- # sl::Plane **Module:** **Spatial Mapping Module** Class representing a plane defined by a point and a normal, or a plane equation. More... `#include ` ## Detailed Description ```cpp class sl::Plane; ``` Class representing a plane defined by a point and a normal, or a plane equation. **Note**: The plane measurements are expressed in reference defined by sl::RuntimeParameters.measure3D_reference_frame. Other elements can be extracted such as the mesh, the 3D bounds, etc. ## Public Functions Documentation ### function Plane ```cpp Plane() ``` Default constructor. ### function ~Plane ```cpp ~Plane() ``` Default destructor. ### function clear ```cpp void clear() ``` Clears all the data. ### function getNormal ```cpp sl::float3 getNormal() ``` Gets the plane normal vector. **Return**: sl::Plane normalized normal vector. ### function getCenter ```cpp sl::float3 getCenter() ``` Gets the plane center point. **Return**: sl::Plane center point. ### function getPose ```cpp Transform getPose() ``` Gets the plane pose relative to the global reference frame. **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. ### function getExtents ```cpp sl::float2 getExtents() ``` Gets the width and height of the bounding rectangle around the plane contours. **Return**: Width and height of the bounding plane contours. **Warning**: This value is expressed in the plane reference frame. ### function getPlaneEquation ```cpp sl::float4 getPlaneEquation() ``` Gets the plane equation. **Return**: Plane equation coefficients `{a, b, c, d}`. **Note**: The plane equation has the following form: `ax + by + cz = d`. ### function getBounds ```cpp std::vector< sl::float3 > getBounds() ``` 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. ### function extractMesh ```cpp sl::Mesh extractMesh() ``` Compute and return the mesh of the bounds polygon. **Return**: sl::Mesh representing the plane delimited by the visible bounds. ### function getClosestDistance ```cpp float getClosestDistance( sl::float3 point =sl::float3(0, 0, 0) ) ``` Gets the distance between the input point and the projected point alongside the normal vector onto the plane (the closest point on the plane). **Parameters**: * **point** : Point to project into the plane. **Return**: The Euclidean distance between the input point and the projected point. ## Public Attributes Documentation ### variable type ```cpp PLANE_TYPE type = PLANE_TYPE::UNKNOWN; ``` 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. * sl::MODEL::ZED will give sl::PLANE_TYPE::UNKNOWN for every planes. --- # sl::PointCloudChunk **Module:** **Spatial Mapping Module** Class representing a sub-point cloud containing local vertices and colors. More... `#include ` ## Detailed Description ```cpp class sl::PointCloudChunk; ``` Class representing a sub-point cloud containing local vertices and colors. **Note**: vertices and normals have the same size. ## Public Functions Documentation ### function PointCloudChunk ```cpp PointCloudChunk() ``` Default constructor. Creates an empty sl::PointCloudChunk. ### function ~PointCloudChunk ```cpp ~PointCloudChunk() ``` Default destructor. ### function clear ```cpp void clear() ``` Clears all data. ## Public Attributes Documentation ### variable vertices ```cpp std::vector< float4 > vertices; ``` Vector of vertices. Vertices are defined by a colored 3D point `{x, y, z, rgba}`. ### variable normals ```cpp std::vector< float3 > normals; ``` Vector of normals. Normals are defined by three components `{nx, ny, nz}`. ### variable timestamp ```cpp unsigned long long timestamp; ``` Timestamp of the latest update. ### variable barycenter ```cpp float3 barycenter; ``` 3D centroid of the chunk. ### variable has_been_updated ```cpp bool has_been_updated; ``` Whether the chunk has been updated by an inner process. --- # sl::PositionalTrackingStatus **Module:** **Positional Tracking Module** Lists the different status of positional tracking. `#include ` ## Public Attributes Documentation ### variable odometry_status ```cpp ODOMETRY_STATUS odometry_status = ODOMETRY_STATUS::UNAVAILABLE; ``` Represents the current state of Visual-Inertial Odometry (VIO) tracking between the previous frame and the current frame. ### variable spatial_memory_status ```cpp SPATIAL_MEMORY_STATUS spatial_memory_status = SPATIAL_MEMORY_STATUS::OFF; ``` Represents the current state of camera tracking in the global map. ### variable tracking_fusion_status ```cpp POSITIONAL_TRACKING_FUSION_STATUS tracking_fusion_status = POSITIONAL_TRACKING_FUSION_STATUS::UNAVAILABLE; ``` Represents the current state of positional tracking fusion. --- # sl::Rect **Module:** **Core Module** Class defining a 2D rectangle with top-left corner coordinates and width/height in pixels. `#include ` ## Public Functions Documentation ### function Rect ```cpp inline Rect( size_t x_ =0, size_t y_ =0, size_t w_ =0, size_t h_ =0 ) ``` Default constructor. ### function area ```cpp inline size_t area() ``` Returns the area of the rectangle. ### function operator== ```cpp inline bool operator==( const Rect & that ) const ``` Tests if the given sl::Rect has the same properties. **Return**: True if all the components matches. ### function operator!= ```cpp inline bool operator!=( const Rect & that ) const ``` Tests if the given sl::Rect has different properties. **Return**: True if one of the components does not match. ### function isEmpty ```cpp inline bool isEmpty() const ``` Tests if the given sl::Rect is empty (width or/and height is null). ### function contains ```cpp inline bool contains( const Rect & target, bool proper =false ) const ``` Tests if this sl::Rect contains the **target**sl::Rect. **Return**: true if this rectangle contains the **target** rectangle, otherwise false. **Note**: This method only returns true if the target rectangle is entirely inside this rectangle (not on the edge). ### function isContained ```cpp inline bool isContained( const Rect & target, bool proper =false ) const ``` 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). ### function isContained ```cpp inline bool isContained( const Resolution & resolution, bool proper =false ) const ``` Overloaded method of isContained(). Tests if this sl::Rect is contained inside a given sl::Resolution. **Return**: true 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). It tests if the current rectangle is contained inside a sl::Rect defined by Rect(0, 0, resolution.width, resolution.height). ## Public Attributes Documentation ### variable x ```cpp size_t x; ``` x coordinates of top-left corner. ### variable y ```cpp size_t y; ``` y coordinates of top-left corner. ### variable width ```cpp size_t width; ``` Width of the rectangle in pixels. ### variable height ```cpp size_t height; ``` Height of the rectangle in pixels. --- # sl::Rotation **Module:** **Positional Tracking Module** Class representing a rotation for the positional tracking module. More... `#include ` Inherits from Matrix3f ## Additional inherited members **Public Functions inherited from Matrix3f** | | Name | | -------------- | -------------- | | | **Matrix3f**()
Default constructor. | | | **Matrix3f**(float data[])
Copy constructor (deep copy). | | | **Matrix3f**(const Matrix3f & mat)
Cpy constructor (deep copy). | | | **Matrix3f**(Matrix3f && mat)
Move constructor. | | Matrix3f & | **operator=**(const Matrix3f & mat)
Copy assignment operator. | | Matrix3f & | **operator=**(Matrix3f && mat)
Move assignment operator. | ## Detailed Description ```cpp class sl::Rotation; ``` Class representing a rotation for the positional tracking module. It inherits from the generic sl::Matrix3f class. ## Public Functions Documentation ### function Rotation ```cpp Rotation() ``` Default constructor. Creates a null rotation. ### function Rotation ```cpp Rotation( const Rotation & rotation ) ``` Copy constructor (deep copy). **Parameters**: * **rotation** : sl::Rotation to copy. ### function Rotation ```cpp Rotation( const Matrix3f & mat ) ``` sl::Rotation constructor from an sl::Matrix3f. **Parameters**: * **mat** : sl::Matrix3f to copy. Copies the sl::Matrix3f (deep copy). ### function Rotation ```cpp Rotation( const Orientation & orientation ) ``` sl::Rotation constructor from an sl::Orientation. **Parameters**: * **orientation** : the Orientation to be used. It converts the Orientation representation to the Rotation one. ### function Rotation ```cpp Rotation( const float angle, const Translation & axis ) ``` sl::Rotation constructor from an angle and an axis. **Parameters**: * **angle** : Rotation angle in radian. * **axis** : 3D axis to rotate around. ### function setOrientation ```cpp void setOrientation( const Orientation & orientation ) ``` Sets the sl::Rotation from an sl::Orientation. **Parameters**: * **orientation** : sl::Orientation containing the rotation to set. ### function getOrientation ```cpp Orientation getOrientation() const ``` Returns the sl::Orientation corresponding to the current sl::Rotation. **Return**: Rotation of the current orientation. ### function getRotationVector ```cpp float3 getRotationVector() ``` Returns the 3x1 rotation vector obtained from 3x3 rotation matrix using Rodrigues formula. **Return**: Rotation vector created from the sl::Orientation values. ### function setRotationVector ```cpp void setRotationVector( const float3 & vec_rot ) ``` Sets the sl::Rotation from a rotation vector (using Rodrigues' transformation). **Parameters**: * **vec_rot** : Vector containing the rotation value for each axis `(rx, ry, rz)`. ### function getEulerAngles ```cpp float3 getEulerAngles( bool radian =true ) const ``` Converts the sl::Rotation into Euler angles. **Parameters**: * **radian** : Whether the angle will be returned in radian or degree. **Return**: Euler angles created from the sl::Rotation values representing the rotations around the X, Y and Z axes using YZX convention. ### function setEulerAngles ```cpp void setEulerAngles( const float3 & euler_angles, bool radian =true ) ``` Sets the sl::Rotation from Euler angles. **Parameters**: * **euler_angles** : Euler angles (as a sl::float3) to update the sl::Rotation. * **radian** : Whether the angle is in radian or degree. ### function operator* ```cpp Matrix3f operator*( const Matrix3f & mat ) const ``` Gives the result of the multiplication between two sl::Matrix3f. ### function operator* ```cpp Matrix3f operator*( const float & scalar ) const ``` Gives the result of the multiplication between a sl::Matrix3f and a scalar. ### function operator+ ```cpp Matrix3f operator+( const Matrix3f & mat ) const ``` Gives the result of the addition between two sl::Matrix3f. ### function operator+ ```cpp Matrix3f operator+( const float & scalar ) const ``` Gives the result of the addition between a sl::Matrix3f and a scalar. ### function operator- ```cpp Matrix3f operator-( const Matrix3f & mat ) const ``` Gives the result of the subtraction between two sl::Matrix3f. ### function operator- ```cpp Matrix3f operator-( const float & scalar ) const ``` Gives the result of the subtraction between a sl::Matrix3f and a scalar. ### function operator== ```cpp bool operator==( const Matrix3f & mat ) const ``` Test two sl::Matrix3f equality. ### function operator!= ```cpp bool operator!=( const Matrix3f & mat ) const ``` Test two sl::Matrix3f inequality. ### function operator() ```cpp float & operator()( int u, int v ) ``` Gets access to a specific point in the sl::Matrix3f (read/write). **Parameters**: * **u** : Row to get the value from. * **v** : Column to get the value from. **Return**: The value at the u, v coordinates. ### function inverse ```cpp void inverse() ``` Sets the sl::Matrix3f to its inverse. ### function transpose ```cpp void transpose() ``` Sets the sl::Matrix3f to its transpose. ### function setIdentity ```cpp void setIdentity() ``` Sets the sl::Matrix3f to identity. ### function setZeros ```cpp void setZeros() ``` Sets the sl::Matrix3f to zero. ### function getInfos ```cpp String getInfos() const ``` Returns the components of the sl::Matrix3f in a sl::String. **Return**: A sl::String containing the components of the current sl::Matrix3f. ### function inverse ```cpp static Matrix3f inverse( const Matrix3f & rotation ) ``` Returns the inverse of a sl::Matrix3f. **Parameters**: * **rotation** : sl::Matrix3f to compute the inverse from. **Return**: The inverse of the sl::Matrix3f given as input. ### function transpose ```cpp static Matrix3f transpose( const Matrix3f & rotation ) ``` Returns the transpose of a sl::Matrix3f. **Parameters**: * **rotation** : sl::Matrix3f to compute the transpose from. **Return**: The transpose of the sl::Matrix3f given as input. ### function identity ```cpp static Matrix3f identity() ``` Creates an identity sl::Matrix3f. **Return**: A sl::Matrix3f set to identity. ### function zeros ```cpp static Matrix3f zeros() ``` Creates a sl::Matrix3f filled with zeros. **Return**: A sl::Matrix3f filled with zeros. ## Public Attributes Documentation ### variable matrix_name ```cpp String matrix_name; ``` Name of the matrix (optional). --- # sl::SensorDeviceIdentifier **Module:** **Sensors Module** Structure containing information about a sensor device (camera or lidar) managed by the Sensors class. More... `#include ` ## Detailed Description ```cpp class sl::SensorDeviceIdentifier; ``` Structure containing information about a sensor device (camera or lidar) managed by the Sensors class. This underlying SensorID value is set into the SensorDeviceIdentifier by calling the Sensors::add function. The sensor_name can be configured to add a custom label to the device. ## Public Functions Documentation ### function SensorDeviceIdentifier ```cpp SensorDeviceIdentifier( std::string sensor_name ="", SENSORS_TYPE type =SENSORS_TYPE::CAMERA ) ``` Default constructor. **Parameters**: * **sensor_name** : Custom name for the device. * **type** : Type of the sensor (Camera, Lidar, etc). ### function getID ```cpp inline SensorID getID() const ``` Returns the unique ID of the sensor. **Return**: The sensor ID. ### function getSerialNumber ```cpp inline uint64_t getSerialNumber() const ``` Returns the serial number of the sensor. **Return**: The serial number. ### function operator< ```cpp inline bool operator<( const SensorDeviceIdentifier & other ) const ``` Comparison operator. ### function operator== ```cpp inline bool operator==( const SensorDeviceIdentifier & other ) const ``` Equality operator. ## Public Attributes Documentation ### variable sensor_name ```cpp std::string sensor_name; ``` Custom name of the camera. ### variable type ```cpp SENSORS_TYPE type; ``` Type of the sensor. --- # sl::Sensors **Module:** **Sensors Module** Class for managing multiple sensors (Cameras, Lidars) and fusing their data. More... `#include ` ## Detailed Description ```cpp class sl::Sensors; ``` Class for managing multiple sensors (Cameras, Lidars) and fusing their data. **Note**: **Beta:** The Sensors API is currently in beta. Interfaces and behavior may change in future SDK releases. The Sensors class allows you to: * Add multiple cameras and lidars. * Synchronize their data. * Retrieve fused data (if available). * Manage settings for each device. ## Public Functions Documentation ### function Sensors ```cpp Sensors() ``` Sensors constructor. ### function ~Sensors ```cpp ~Sensors() ``` Sensors destructor. ### function init ```cpp SENSORS_ERROR_CODE init( const sl::InitSensorsParameters & init_parameters =InitSensorsParameters() ) ``` Initializes the Sensors instance. This function should be called only once and before any other function. **Parameters**: * **init_parameters** : The initialization parameters. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. ### function add ```cpp SENSORS_ERROR_CODE add( const sl::InitParameters & init_parameters, sl::SensorDeviceIdentifier & camera_identifier_out ) ``` Adds a camera to the Sensors instance. This function starts the camera and fills the SensorDeviceIdentifier. It should be used for each camera in the system. It is advised to add all cameras, then enable modules. A module cannot include a camera that was not yet added. **Parameters**: * **init_parameters** : The initialization parameters for the camera. * **camera_identifier_out** : The identifier of the added camera. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. ### function add ```cpp SENSORS_ERROR_CODE add( const sl::InitParametersOne & init_parameters, sl::SensorDeviceIdentifier & camera_identifier_out ) ``` Adds a ZED One camera to the Sensors instance. **Parameters**: * **init_parameters** : The initialization parameters for the ZED One camera. * **camera_identifier_out** : The identifier of the added camera. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. ### function add ```cpp SENSORS_ERROR_CODE add( const sl::InitLidarParameters & init_parameters, sl::SensorDeviceIdentifier & camera_identifier_out ) ``` Adds a Lidar to the Sensors instance. **Parameters**: * **init_parameters** : The initialization parameters for the Lidar. * **camera_identifier_out** : The identifier of the added Lidar. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. ### function remove ```cpp SENSORS_ERROR_CODE remove( sl::SensorDeviceIdentifier & unique_identifier ) ``` Stops a sensor and removes it from the instance. This also removes the sensor from all module instances. **Parameters**: * **unique_identifier** : The identifier of the sensor to remove. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. ### function setSensorPose ```cpp SENSORS_ERROR_CODE setSensorPose( const sl::Transform & pose, sl::SensorDeviceIdentifier unique_identifier =defaultSensorDeviceIdentifier() ) =default ``` Updates the sensor pose relative to the system frame. **Parameters**: * **pose** : The new pose. * **unique_identifier** : The identifier of the sensor. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. ### function getSensorPose ```cpp SENSORS_ERROR_CODE getSensorPose( sl::Transform & pose, sl::SensorDeviceIdentifier unique_identifier =defaultSensorDeviceIdentifier() ) =default ``` Gets the sensor pose relative to the system frame. **Parameters**: * **pose** : The retrieved pose. * **unique_identifier** : The identifier of the sensor. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. ### function getSensorsID ```cpp SENSORS_ERROR_CODE getSensorsID( std::set< SensorDeviceIdentifier > & sensors_identifier ) ``` Gets the list of all current active sensors IDs. **Parameters**: * **sensors_identifier** : The set of active sensor identifiers. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. ### function read ```cpp SENSORS_ERROR_CODE read() ``` Reads the latest images and IMU from all sensors and rectifies the images. This function is meant to be called before Sensors::process(). **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. ### function process ```cpp SENSORS_ERROR_CODE process() ``` Processes data from all sensors. This method will call read() if it hasn't been called, then call each sensor's grab in parallel to compute all measures and fused data. This is the main function to be called in a loop. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. **Note**: In pipelined mode (execution_mode == PIPELINED): * First call: Runs synchronously (setup phase — learns which outputs the user needs) * After the first process()+retrieve*() cycle: subsequent process() calls return immediately (worker threads running in background) ### function getErrorCodes ```cpp SENSORS_ERROR_CODE getErrorCodes( BatchedData< sl::ERROR_CODE > & errs ) ``` Gets the list of individual ERROR_CODE returned by each sensor in the last function call. **Parameters**: * **errs** : A map of sensor ID to error code. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. ### function getProcessErrorCodes ```cpp SENSORS_ERROR_CODE getProcessErrorCodes( BatchedData< sl::ERROR_CODE > & errs ) ``` Gets the list of individual ERROR_CODE returned by each sensor in the last read/process function call. **Parameters**: * **errs** : A map of sensor ID to error code. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. ### function setRuntimeSensorsParameters ```cpp SENSORS_ERROR_CODE setRuntimeSensorsParameters( const RuntimeSensorsParameters & params =RuntimeSensorsParameters() ) ``` Sets the runtime parameters of Sensors used by process. **Parameters**: * **params** : The runtime parameters. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. ### function syncSVO ```cpp SENSORS_ERROR_CODE syncSVO( sl::Timestamp t =sl::Timestamp() ) ``` Synchronizes all sensors when the input used is SVO/OSF files. It finds the earliest common timestamp across all camera SVOs and LiDAR OSFs, then sets the playback position of each sensor to that common timestamp. This ensures all sensors start playback from the same point in time. **Parameters**: * **t** : The timestamp to sync to. If 0 (default), automatically finds the latest start timestamp among all files. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if all sensors were synchronized successfully. **Note**: This function should be called once all sensors are added and they have SVO/OSF input type. ### function setSVOPositionAtTimestamp ```cpp SENSORS_ERROR_CODE setSVOPositionAtTimestamp( const sl::Timestamp & timestamp ) ``` Seeks all sensors to a specific timestamp. This function sets the playback position of all SVO/OSF files to the frame closest to the specified timestamp. It's useful for jumping to a specific point in time during multi-sensor playback. **Parameters**: * **timestamp** : The timestamp to seek to. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if all sensors were repositioned successfully. **Note**: The method works only for sensors opened with SVO/OSF input. **Warning**: Using this function creates a jump in time which will reset modules like positional tracking. ### function retrieveImage ```cpp SENSORS_ERROR_CODE retrieveImage( sl::Mat & mat, const sl::VIEW view =VIEW::LEFT, const sl::MEM type =MEM::CPU, const sl::Resolution image_size =Resolution(0, 0), sl::SensorDeviceIdentifier unique_identifier =defaultSensorDeviceIdentifier() ) =default ``` Returns the current VIEW of the specified camera. **Parameters**: * **mat** : The retrieved image. * **view** : The view to retrieve. * **type** : The memory type (CPU/GPU). * **image_size** : The resolution of the output image. * **unique_identifier** : The camera identifier. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. ### function retrieveMeasure ```cpp SENSORS_ERROR_CODE retrieveMeasure( sl::Mat & mat, const sl::MEASURE measure =MEASURE::DEPTH, const sl::MEM type =MEM::CPU, const sl::Resolution image_size =Resolution(0, 0), sl::SensorDeviceIdentifier unique_identifier =defaultSensorDeviceIdentifier() ) =default ``` Returns the current MEASURE of the specified camera. **Parameters**: * **mat** : The retrieved measure. * **measure** : The measure to retrieve. * **type** : The memory type (CPU/GPU). * **image_size** : The resolution of the output measure. * **unique_identifier** : The camera identifier. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. ### function getMotionSensorsData ```cpp SENSORS_ERROR_CODE getMotionSensorsData( sl::SensorsData & data, sl::TIME_REFERENCE reference_time, sl::SensorDeviceIdentifier unique_identifier =defaultSensorDeviceIdentifier() ) =default ``` Returns the current SensorsData (IMU, magnetometer, barometer) of the specified sensor. **Parameters**: * **data** : The retrieved motion sensors data. * **reference_time** : The time reference. * **unique_identifier** : The sensor identifier. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. ### function getCameraInformation ```cpp CameraInformation getCameraInformation( Resolution image_size =Resolution(0, 0), sl::SensorDeviceIdentifier unique_identifier =defaultSensorDeviceIdentifier() ) =default ``` Returns the CameraInformation associated the camera being used. **Parameters**: * **image_size** : The resolution for the calibration parameters. * **unique_identifier** : The camera identifier. **Return**: The camera information. ### function updateSelfCalibration ```cpp void updateSelfCalibration( sl::SensorDeviceIdentifier unique_identifier =defaultSensorDeviceIdentifier() ) =default ``` Performs a new self-calibration process for the specified camera. 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. **Parameters**: * **unique_identifier** : The camera identifier. **Note**: The self calibration will occur at the next process() call. **Warning**: New values will then be available in getCameraInformation(), be sure to get them to still have consistent 2D <-> 3D conversion. ### function retrieveImage ```cpp SENSORS_ERROR_CODE retrieveImage( BatchedData< sl::Mat > & mat_list, const sl::VIEW view =VIEW::LEFT, const sl::MEM type =MEM::CPU, const sl::Resolution image_size =Resolution(0, 0), std::set< SensorDeviceIdentifier > sensors_ids ={} ) ``` Returns the VIEW of all the specified sensors. If `sensors_ids` is empty or if the set contains defaultSensorDeviceIdentifier(), it will return images from all the sensors of the system. **Parameters**: * **mat_list** : The retrieved images. * **view** : The view to retrieve. * **type** : The memory type (CPU/GPU). * **image_size** : The resolution of the output images. * **sensors_ids** : The set of sensor identifiers to retrieve. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. ### function retrieveMeasure ```cpp SENSORS_ERROR_CODE retrieveMeasure( BatchedData< sl::Mat > & mat_list, const sl::MEASURE measure =MEASURE::DEPTH, const sl::MEM type =MEM::CPU, const sl::Resolution image_size =Resolution(0, 0), std::set< SensorDeviceIdentifier > sensors_ids ={} ) ``` Returns the MEASURE of all the specified sensors. If `sensors_ids` is empty or if the set contains defaultSensorDeviceIdentifier(), it will return measures from all the sensors of the system. **Parameters**: * **mat_list** : The retrieved measures. * **measure** : The measure to retrieve. * **type** : The memory type (CPU/GPU). * **image_size** : The resolution of the output measures. * **sensors_ids** : The set of sensor identifiers to retrieve. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. ### function retrieveMeasure ```cpp SENSORS_ERROR_CODE retrieveMeasure( BatchedData< sl::Mat > & mat_list, const sl::LIDAR_MEASURE measure =LIDAR_MEASURE::XYZ, const sl::MEM type =MEM::CPU, const sl::Resolution image_size =Resolution(0, 0), std::set< SensorDeviceIdentifier > sensors_ids ={} ) ``` Returns the LIDAR_MEASURE of all the specified sensors (Lidar). If `sensors_ids` is empty or if the set contains defaultSensorDeviceIdentifier(), it will return measures from all the sensors of the system (if applicable). **Parameters**: * **mat_list** : The retrieved measures. * **measure** : The lidar measure to retrieve. * **type** : The memory type (CPU/GPU). * **image_size** : The resolution of the output measures. * **sensors_ids** : The set of sensor identifiers to retrieve. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. ### function getMotionSensorsData ```cpp SENSORS_ERROR_CODE getMotionSensorsData( BatchedData< sl::SensorsData > & data, sl::TIME_REFERENCE reference_time, std::set< SensorDeviceIdentifier > sensors_ids ={} ) ``` Returns the SensorsData (IMU, magnetometer, barometer) of all the specified sensors. If `sensors_ids` is empty or if the set contains defaultSensorDeviceIdentifier(), it will return SensorsData from all the sensors of the system. **Parameters**: * **data** : The retrieved sensors data. * **reference_time** : The time reference. * **sensors_ids** : The set of sensor identifiers to retrieve. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. ### function getCurrentFPS ```cpp SENSORS_ERROR_CODE getCurrentFPS( BatchedData< float > & data, std::set< SensorDeviceIdentifier > sensors_ids ={} ) ``` Returns the current compute FPS of all the specified sensors. If `sensors_ids` is empty or if the set contains defaultSensorDeviceIdentifier(), it will return the data from all the sensors of the system. **Parameters**: * **data** : The retrieved FPS. * **sensors_ids** : The set of sensor identifiers query. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. ### function getCurrentFPS ```cpp SENSORS_ERROR_CODE getCurrentFPS( float & fps, sl::SensorDeviceIdentifier unique_identifier =defaultSensorDeviceIdentifier() ) =default ``` Returns the current compute FPS of the specified camera. **Parameters**: * **fps** : The retrieved FPS. * **unique_identifier** : The camera identifier. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. ### function getFrameDroppedCount ```cpp SENSORS_ERROR_CODE getFrameDroppedCount( BatchedData< unsigned int > & data, std::set< SensorDeviceIdentifier > sensors_ids ={} ) ``` Returns the frame dropped count of all the specified sensors. If `sensors_ids` is empty or if the set contains defaultSensorDeviceIdentifier(), it will return the data from all the sensors of the system. **Parameters**: * **data** : The retrieved dropped frame counts. * **sensors_ids** : The set of sensor identifiers query. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. ### function getFrameDroppedCount ```cpp SENSORS_ERROR_CODE getFrameDroppedCount( unsigned int & count, sl::SensorDeviceIdentifier unique_identifier =defaultSensorDeviceIdentifier() ) =default ``` Returns the frame dropped count of the specified sensor. **Parameters**: * **count** : The retrieved dropped frame count. * **unique_identifier** : The sensor identifier. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. ### function getTimestamp ```cpp SENSORS_ERROR_CODE getTimestamp( BatchedData< Timestamp > & data, sl::TIME_REFERENCE reference_time, std::set< SensorDeviceIdentifier > sensors_ids ={} ) ``` Returns the timestamp of all the specified sensors. If `sensors_ids` is empty or if the set contains defaultSensorDeviceIdentifier(), it will return the data from all the sensors of the system. **Parameters**: * **data** : The retrieved timestamps. * **reference_time** : The time reference (IMAGE or CURRENT). * **sensors_ids** : The set of sensor identifiers query. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. ### function getHealthStatus ```cpp SENSORS_ERROR_CODE getHealthStatus( BatchedData< HealthStatus > & data, std::set< SensorDeviceIdentifier > sensors_ids ={} ) ``` Returns the health status of all the specified sensors. If `sensors_ids` is empty or if the set contains defaultSensorDeviceIdentifier(), it will return the data from all the sensors of the system. **Parameters**: * **data** : The retrieved health statuses. * **sensors_ids** : The set of sensor identifiers query. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. ### function setRegionOfInterest ```cpp SENSORS_ERROR_CODE setRegionOfInterest( sl::Mat & roi_mask, std::unordered_set< MODULE > module ={MODULE::ALL}, sl::SensorDeviceIdentifier unique_identifier =defaultSensorDeviceIdentifier() ) =default ``` Defines a region of interest to focus on for all the SDK, discarding other parts for the specified camera. **Parameters**: * **roi_mask** : The mask defining the region of interest. * **module** : The module to apply the ROI to. * **unique_identifier** : The camera identifier. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. ### function getRegionOfInterest ```cpp SENSORS_ERROR_CODE getRegionOfInterest( sl::Mat & roi_mask, sl::Resolution image_size =Resolution(0, 0), MODULE module =MODULE::ALL, sl::SensorDeviceIdentifier unique_identifier =defaultSensorDeviceIdentifier() ) =default ``` Gets the previously set or computed region of interest. **Parameters**: * **roi_mask** : The mask defining the region of interest. * **image_size** : The size of the mask. * **module** : The module the ROI applies to. * **unique_identifier** : The camera identifier. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. ### function startRegionOfInterestAutoDetection ```cpp SENSORS_ERROR_CODE startRegionOfInterestAutoDetection( sl::RegionOfInterestParameters roi_param =sl::RegionOfInterestParameters(), sl::SensorDeviceIdentifier unique_identifier =defaultSensorDeviceIdentifier() ) =default ``` Starts the auto detection of a region of interest to focus on for all the SDK, discarding other parts for the specified camera. 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, as an internal motion detector is used (based on the Positional Tracking module). It requires a few hundreds frames of motion to compute the mask. **Parameters**: * **roi_param** : Parameters for ROI auto detection. * **unique_identifier** : The camera identifier. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. ### function getRegionOfInterestAutoDetectionStatus ```cpp SENSORS_ERROR_CODE getRegionOfInterestAutoDetectionStatus( REGION_OF_INTEREST_AUTO_DETECTION_STATE & status, sl::SensorDeviceIdentifier unique_identifier =defaultSensorDeviceIdentifier() ) =default ``` Returns the status of the automatic Region of Interest Detection for the specified camera. The automatic Region of Interest Detection is enabled by using startRegionOfInterestAutoDetection. **Parameters**: * **status** : The current status of the auto detection. * **unique_identifier** : The camera identifier. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. ### function getCameraSettings ```cpp SENSORS_ERROR_CODE getCameraSettings( VIDEO_SETTINGS settings, int & setting, SensorDeviceIdentifier sensors_id =defaultSensorDeviceIdentifier() ) =default ``` Returns the current value of the requested camera setting (gain, brightness, hue, exposure, etc.). **Parameters**: * **settings** : The setting to retrieve. * **setting** : The retrieved value. * **sensors_id** : The sensor identifier. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. Possible values (range) of each setting are available here. ### function getCameraSettings ```cpp SENSORS_ERROR_CODE getCameraSettings( VIDEO_SETTINGS settings, int & min_val, int & max_val, SensorDeviceIdentifier sensors_id =defaultSensorDeviceIdentifier() ) =default ``` Returns the current range of the requested settings for settings that support min/max values. **Parameters**: * **settings** : The setting to retrieve. * **min_val** : The retrieved minimum value. * **max_val** : The retrieved maximum value. * **sensors_id** : The sensor identifier. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. **Note**: Works only with ZED X that supports low-level controls. 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 ### function getCameraSettings ```cpp SENSORS_ERROR_CODE getCameraSettings( VIDEO_SETTINGS settings, Rect & roi, sl::SIDE side =sl::SIDE::BOTH, SensorDeviceIdentifier sensors_id =defaultSensorDeviceIdentifier() ) =default ``` Overloaded method for VIDEO_SETTINGS::AEC_AGC_ROI which takes a Rect as parameter. **Parameters**: * **settings** : The setting to retrieve. * **roi** : The retrieved ROI. * **side** : The side (Left/Right/Both). * **sensors_id** : The sensor identifier. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. **Note**: * Works only if the camera is open in LIVE or STREAM mode with VIDEO_SETTINGS::AEC_AGC_ROI. * It will return SENSORS_ERROR_CODE::INVALID_FUNCTION_CALL or SENSORS_ERROR_CODE::INVALID_FUNCTION_PARAMETERS otherwise. ### function getCameraSettingsRange ```cpp SENSORS_ERROR_CODE getCameraSettingsRange( VIDEO_SETTINGS settings, int & min, int & max, SensorDeviceIdentifier sensors_id =defaultSensorDeviceIdentifier() ) =default ``` Returns the range for the specified VIDEO_SETTINGS as min/max value. **Parameters**: * **settings** : The setting to retrieve range for. * **min** : The retrieved minimum value. * **max** : The retrieved maximum value. * **sensors_id** : The sensor identifier. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. ### function isCameraSettingSupported ```cpp SENSORS_ERROR_CODE isCameraSettingSupported( VIDEO_SETTINGS setting, bool & is_supported_list, SensorDeviceIdentifier sensors_id =defaultSensorDeviceIdentifier() ) =default ``` Checks if the video setting is supported by the camera. **Parameters**: * **setting** : The setting to check. * **is_supported_list** : True if supported. * **sensors_id** : The sensor identifier. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. ### function setCameraSettings ```cpp SENSORS_ERROR_CODE setCameraSettings( VIDEO_SETTINGS settings, int value =VIDEO_SETTINGS_VALUE_AUTO, SensorDeviceIdentifier sensors_id =defaultSensorDeviceIdentifier() ) =default ``` Sets the value of the requested camera setting (gain, brightness, hue, exposure, etc.). **Parameters**: * **settings** : The setting to set. * **value** : The value to set (default: VIDEO_SETTINGS_VALUE_AUTO). * **sensors_id** : The sensor identifier. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. **Note**: The method works only if the camera is open in LIVE or STREAM mode. **Warning**: Setting VIDEO_SETTINGS::EXPOSURE or VIDEO_SETTINGS::GAIN to default will automatically sets the other to default. This method only applies for VIDEO_SETTINGS that require a single value. ### function setCameraSettings ```cpp SENSORS_ERROR_CODE setCameraSettings( VIDEO_SETTINGS settings, int min, int max, SensorDeviceIdentifier sensors_id =defaultSensorDeviceIdentifier() ) =default ``` Sets the value of the requested camera setting that supports two values (min/max). This method only works with the following VIDEO_SETTINGS: * VIDEO_SETTINGS::AUTO_EXPOSURE_TIME_RANGE * VIDEO_SETTINGS::AUTO_ANALOG_GAIN_RANGE * VIDEO_SETTINGS::AUTO_DIGITAL_GAIN_RANGEsettings: The setting to set. min: The minimum value. max: The maximum value. sensors_id: The sensor identifier. [SENSORS_ERROR_CODE::SUCCESS] if successful. ### function setCameraSettings ```cpp SENSORS_ERROR_CODE setCameraSettings( VIDEO_SETTINGS settings, Rect roi, sl::SIDE side =sl::SIDE::BOTH, bool reset =false, SensorDeviceIdentifier sensors_id =defaultSensorDeviceIdentifier() ) =default ``` Overloaded method for VIDEO_SETTINGS::AEC_AGC_ROI which takes a Rect as parameter. **Parameters**: * **settings** : The setting to set. * **roi** : The ROI to set. * **side** : The side (Left/Right/Both). * **reset** : Whether to reset the ROI. * **sensors_id** : The sensor identifier. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. ### function enableObjectDetection ```cpp SENSORS_ERROR_CODE enableObjectDetection( const sl::ObjectDetectionSensorsParameters & param ) ``` Initializes and starts object detection module instance. This function should be called after all cameras are added and before any other function of the module. **Parameters**: * **param** : The object detection parameters. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. **Note**: The object detection module can be used with multiple instances. ### function setObjectDetectionRuntimeParameters ```cpp SENSORS_ERROR_CODE setObjectDetectionRuntimeParameters( const ObjectDetectionRuntimeParameters & params, const unsigned int instance_id =0, std::set< sl::SensorDeviceIdentifier > cam_identifiers ={} ) ``` Sets the runtime parameters of the object detection module. By default the object detection module will use the parameters set in the ObjectDetectionRuntimeParameters constructor. This can be changed at any time and will be used for the specified cameras of the instance. Since the processing is done in parallel, the parameters will be used for the next inference. **Parameters**: * **params** : The runtime parameters. * **instance_id** : The instance ID. * **cam_identifiers** : The set of camera identifiers to apply parameters to. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. ### function setCustomObjectDetectionRuntimeParameters ```cpp SENSORS_ERROR_CODE setCustomObjectDetectionRuntimeParameters( const CustomObjectDetectionRuntimeParameters & params, const unsigned int instance_id =0, std::set< sl::SensorDeviceIdentifier > cam_identifiers ={} ) ``` Sets the custom runtime parameters of the object detection module. By default the object detection module will use the parameters set in the CustomObjectDetectionRuntimeParameters constructor. This can be changed at any time and will be used for the specified cameras of the instance. Since the processing is done in parallel, the parameters will be used for the next inference. **Parameters**: * **params** : The custom runtime parameters. * **instance_id** : The instance ID. * **cam_identifiers** : The set of camera identifiers to apply parameters to. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. ### function ingestCustomBoxObjects ```cpp SENSORS_ERROR_CODE ingestCustomBoxObjects( const std::vector< CustomBoxObjectData > & objects_in, const unsigned int instance_id =0, sl::SensorDeviceIdentifier unique_identifier =defaultSensorDeviceIdentifier() ) =default ``` Feeds the 3D Object tracking method with your own 2D bounding boxes from your own detection algorithm. **Parameters**: * **objects_in** : The input custom objects. * **instance_id** : The instance ID. * **unique_identifier** : The camera identifier. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. **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 informations and perform object tracking. It's strongly advised to use the read() function, retrieving the left image, running the inference and the ingest, then calling the process() method. ### function ingestCustomMaskObjects ```cpp SENSORS_ERROR_CODE ingestCustomMaskObjects( const std::vector< CustomMaskObjectData > & objects_in, const unsigned int instance_id =0, sl::SensorDeviceIdentifier unique_identifier =defaultSensorDeviceIdentifier() ) =default ``` Feeds the 3D Object tracking method with your own 2D masks from your own detection algorithm. **Parameters**: * **objects_in** : The input custom objects. * **instance_id** : The instance ID. * **unique_identifier** : The camera identifier. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. **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 informations and perform object tracking. It's strongly advised to use the read() function, retrieving the left image, running the inference and the ingest, then calling the process() method. ### function retrieveObjects ```cpp SENSORS_ERROR_CODE retrieveObjects( sl::Objects & objects, SensorDeviceIdentifier sensors_id =defaultSensorDeviceIdentifier(), unsigned int instance_module_id =0 ) =default ``` Retrieves the raw objects data of the specified object detection instance and sensor. **Parameters**: * **objects** : The retrieved objects. * **sensors_id** : The sensor identifier. * **instance_module_id** : The instance ID. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. ### function disableObjectDetection ```cpp SENSORS_ERROR_CODE disableObjectDetection( unsigned int instance_module_id =0 ) ``` Disables the object detection module instance. **Parameters**: * **instance_module_id** : The instance ID. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. ### function enableBodyTracking ```cpp SENSORS_ERROR_CODE enableBodyTracking( const sl::BodyTrackingSensorsParameters & param ) ``` Initializes and starts body tracking module instance. This function should be called after all cameras are added and before any other function of the module. **Parameters**: * **param** : The body tracking parameters. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. **Note**: The body tracking module can be used with multiple instances. ### function setBodyTrackingRuntimeParameters ```cpp SENSORS_ERROR_CODE setBodyTrackingRuntimeParameters( const BodyTrackingSensorsRuntimeParameters & params, const unsigned int instance_id =0, std::set< sl::SensorDeviceIdentifier > cam_identifiers ={} ) ``` Sets the runtime parameters of the body tracking module. By default the body tracking module will use the parameters set in the BodyTrackingRuntimeParameters constructor. This can be changed at any time and will be used for the specified cameras of the instance. Since the processing is done in parallel, the parameters will be used for the next inference. **Parameters**: * **params** : The runtime parameters. * **instance_id** : The instance ID. * **cam_identifiers** : The set of camera identifiers to apply parameters to. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. ### function retrieveBodies ```cpp SENSORS_ERROR_CODE retrieveBodies( sl::Bodies & bodies, SensorDeviceIdentifier sensors_id =defaultSensorDeviceIdentifier(), unsigned int instance_module_id =0 ) =default ``` Retrieves the raw tracked bodies of the specified sensor of the specified instance. **Parameters**: * **bodies** : The retrieved bodies. * **sensors_id** : The sensor identifier. * **instance_module_id** : The instance ID. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. ### function disableBodyTracking ```cpp SENSORS_ERROR_CODE disableBodyTracking( unsigned int instance_module_id =0 ) ``` Disables the body tracking module instance. **Parameters**: * **instance_module_id** : The instance ID. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. ### function enablePositionalTracking ```cpp SENSORS_ERROR_CODE enablePositionalTracking( const PositionalTrackingSensorsParameters & tracking_parameters =PositionalTrackingSensorsParameters(), std::set< SensorDeviceIdentifier > sensors_id ={} ) ``` Initializes and starts the positional tracking processes. **Parameters**: * **tracking_parameters** : The positional tracking parameters. * **sensors_id** : The set of sensor identifiers to enable tracking for. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. ### function getPosition ```cpp POSITIONAL_TRACKING_STATE getPosition( Pose & camera_pose, SENSORS_REFERENCE_FRAME reference_frame =SENSORS_REFERENCE_FRAME::WORLD, SensorDeviceIdentifier sensors_id =defaultSensorDeviceIdentifier() ) =default ``` Retrieves the estimated position and orientation of the sensor in the specified referenceframe". **Parameters**: * **camera_pose** : The retrieved pose. * **reference_frame** : The reference frame for the pose. * **sensors_id** : The sensor identifier. **Return**: The positional tracking state. **Note**: The position is provided in the InitSensorsParameters::coordinate_system . See COORDINATE_SYSTEM for its physical origin. **Warning**: This method requires the tracking to be enabled. enablePositionalTracking() . * Using SENSORS_REFERENCE_FRAME::SENSOR, the returned pose is in the sensor's local frame. * Using SENSORS_REFERENCE_FRAME::BASELINK, the returned pose is transformed by the sensor's extrinsic calibration. * Using SENSORS_REFERENCE_FRAME::WORLD, the returned pose relates to the initial position of the camera (PositionalTrackingSensorsParameters::initial_world_transforms ). * Using SENSORS_REFERENCE_FRAME::DEFAULT, uses the RuntimeSensorsParameters::reference_frame setting. ### function getPosition ```cpp SENSORS_ERROR_CODE getPosition( BatchedData< std::pair< Pose, POSITIONAL_TRACKING_STATE >> & camera_poses, SENSORS_REFERENCE_FRAME reference_frame =SENSORS_REFERENCE_FRAME::WORLD, std::set< SensorDeviceIdentifier > sensors_id ={} ) ``` Retrieves the position and orientation of each sensor in the specified reference frame. **Parameters**: * **camera_poses** : The retrieved poses and tracking states. * **reference_frame** : The reference frame for the poses. * **sensors_id** : The set of sensor identifiers to retrieve. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. ### function resetPositionalTracking ```cpp SENSORS_ERROR_CODE resetPositionalTracking( const Transform & path, std::set< SensorDeviceIdentifier > sensors_ids ={} ) ``` Resets the tracking, and re-initializes the position with the given transformation matrix for the specified cameras. **Parameters**: * **path** : Position of the camera in the world frame when the method is called. * **sensors_ids** : The set of sensor identifiers to reset tracking for. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. **Note**: Please note that this method will also flush the accumulated or loaded spatial memory. ### function disablePositionalTracking ```cpp void disablePositionalTracking( String area_file_path ="" ) ``` Disables the positional tracking. **Parameters**: * **area_file_path** : The path to save the area map to. The positional tracking is immediately stopped. If a file path is given, saveAreaMap() will be called asynchronously. See getAreaExportState() to get the exportation state. If the tracking has been enabled, this function will automatically be called by close() . ### function isPositionalTrackingEnabled ```cpp bool isPositionalTrackingEnabled() ``` Returns whether the positional tracking module is enabled. **Return**: True if positional tracking is enabled. ### function getPositionalTrackingStatus ```cpp sl::PositionalTrackingStatus getPositionalTrackingStatus( SensorDeviceIdentifier sensors_id =defaultSensorDeviceIdentifier() ) =default ``` Returns the current status of positional tracking module. **Parameters**: * **sensors_id** : The sensor identifier. **Return**: The positional tracking status. ### function saveAreaMap ```cpp SENSORS_ERROR_CODE saveAreaMap( String area_file_path, SensorDeviceIdentifier sensors_id =defaultSensorDeviceIdentifier() ) =default ``` Saves the current area learning file. The file will contain spatial memory data generated by the tracking. If the tracking has been initialized with PositionalTrackingSensorsParameters::enable_area_memory to true (default), the method allows you to export the spatial memory. Reloading the exported file in a future session with PositionalTrackingSensorsParameters::area_file_path initializes the tracking within the same referential. This method is asynchronous, and only triggers the file generation. You can use getAreaExportState() to get the export state. The positional tracking keeps running while exporting. ### function getAreaExportState ```cpp AREA_EXPORTING_STATE getAreaExportState( SensorDeviceIdentifier sensors_id =defaultSensorDeviceIdentifier() ) =default ``` Returns the state of the spatial memory export process. As saveAreaMap() only starts the exportation, this method allows you to know when the exportation finished or if it failed. ### function enableRecording ```cpp SENSORS_ERROR_CODE enableRecording( const RecordingSensorsParameters & recording_parameters ) ``` Enable recording module to creates an SVO file for the specified cameras. 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. ### function getRecordingStatus ```cpp RecordingStatus getRecordingStatus( const SensorDeviceIdentifier & sensors_id =defaultSensorDeviceIdentifier() ) =default ``` Returns the recording status information. **Parameters**: * **sensors_id** : The sensor identifier. **Return**: The recording status. ### function pauseRecording ```cpp void pauseRecording( bool status, const SensorDeviceIdentifier & sensors_id =defaultSensorDeviceIdentifier() ) =default ``` Pauses or resumes the recording. **Parameters**: * **status** : If true, the recording is paused. If false, the recording is resumed. * **sensors_id** : The sensor identifier. ### function disableRecording ```cpp void disableRecording( const std::set< SensorDeviceIdentifier > & sensors_ids ={} ) ``` Disables the recording initiated by enableRecording() and closes the generated file. **Parameters**: * **sensors_ids** : The set of sensor identifiers to stop recording for. **Note**: This method will automatically be called by close() if enableRecording() was called. ### function getSVOPosition ```cpp SENSORS_ERROR_CODE getSVOPosition( int & svo_position, sl::SensorDeviceIdentifier unique_identifier =defaultSensorDeviceIdentifier() ) =default ``` 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 read() call increases this value by one (except when using SVO real-time mode). **Parameters**: * **svo_position** : The current frame position. * **unique_identifier** : The camera identifier. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. **Note**: The method works only if the camera is open in SVO playback mode. ### function getSVOPositionAtTimestamp ```cpp SENSORS_ERROR_CODE getSVOPositionAtTimestamp( int & svo_position, const sl::Timestamp & timestamp, sl::SensorDeviceIdentifier unique_identifier =defaultSensorDeviceIdentifier() ) =default ``` Retrieves the frame index within the SVO file corresponding to the provided timestamp. **Parameters**: * **svo_position** : The retrieved SVO position. * **timestamp** : The timestamp to search for. * **unique_identifier** : The camera identifier. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. ### function setSVOPosition ```cpp SENSORS_ERROR_CODE setSVOPosition( int svo_position, sl::SensorDeviceIdentifier unique_identifier =defaultSensorDeviceIdentifier() ) =default ``` Sets the playback cursor to the desired frame number in the SVO file. This method allows you to move around within a played-back SVO file. After calling, the next call to read() will read the provided frame number. **Parameters**: * **svo_position** : The frame number to jump to. * **unique_identifier** : The camera identifier. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. **Note**: The method works only if the camera is open in SVO playback mode. **Warning**: Using this function is not a standard behavior as it creates a jump in time, backward or forward (which can not happen in live conditions). This function will then reset many modules such as positional tracking or spatial mapping. ### function getSVONumberOfFrames ```cpp SENSORS_ERROR_CODE getSVONumberOfFrames( int & number_of_frames, sl::SensorDeviceIdentifier unique_identifier =defaultSensorDeviceIdentifier() ) =default ``` Returns the number of frames in the SVO file. **Parameters**: * **number_of_frames** : The total number of frames in the SVO file. * **unique_identifier** : The camera identifier. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. **Note**: The method works only if the camera is open in SVO playback mode. ### function ingestDataIntoSVO ```cpp SENSORS_ERROR_CODE ingestDataIntoSVO( const sl::SVOData & data, sl::SensorDeviceIdentifier unique_identifier =defaultSensorDeviceIdentifier() ) =default ``` Ingest custom user SVOData in a SVO file. **Parameters**: * **data** : The SVO data to ingest. * **unique_identifier** : The camera identifier. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. **Note**: The method works only if the camera is recording. ### function retrieveSVOData ```cpp SENSORS_ERROR_CODE retrieveSVOData( const std::string & key, std::map< sl::Timestamp, sl::SVOData > & data, sl::Timestamp ts_begin =0, sl::Timestamp ts_end =0, sl::SensorDeviceIdentifier unique_identifier =defaultSensorDeviceIdentifier() ) =default ``` Retrieves SVO data from the SVO file at the given channel key and in the given timestamp range. **Parameters**: * **key** : The key of the SVOData that is going to be retrieved. * **data** : The map to be filled with SVOData objects, with timestamps as keys. * **ts_begin** : The beginning of the range. * **ts_end** : The end of the range. * **unique_identifier** : The camera identifier. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. **Note**: The method works only if the camera is in SVO reading mode. ### function getSVODataKeys ```cpp SENSORS_ERROR_CODE getSVODataKeys( std::vector< std::string > & keys, sl::SensorDeviceIdentifier unique_identifier =defaultSensorDeviceIdentifier() ) =default ``` Get the external (custom data) channels that can be retrieved from the SVO file. **Parameters**: * **keys** : The list of available keys. * **unique_identifier** : The camera identifier. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. **Note**: The method works only if the camera is in SVO reading mode. ### function enableStreaming ```cpp SENSORS_ERROR_CODE enableStreaming( const StreamingSensorsParameters & streaming_parameters =StreamingSensorsParameters() ) ``` Creates a streaming pipeline. **Parameters**: * **streaming_parameters** : A structure containing all the specific parameters for the streaming. Default: a reset of StreamingParameters . **Return**: * SENSORS_ERROR_CODE::SUCCESS if streaming was successfully started. * SENSORS_ERROR_CODE::INVALID_FUNCTION_CALL if open() was not successfully called before. * SENSORS_ERROR_CODE::FAILURE if streaming RTSP protocol was not able to start. * SENSORS_ERROR_CODE::NO_GPU_COMPATIBLE if streaming codec is not supported (in this case, use H264 codec which is supported on all NVIDIA GPU the ZED SDK supports). ### function disableStreaming ```cpp void disableStreaming( const std::set< SensorDeviceIdentifier > & sensors_ids ={} ) ``` Disables the streaming initiated by enableStreaming(). **Parameters**: * **sensors_ids** : The set of sensor identifiers to stop streaming for. **Note**: This method will automatically be called by close() if enableStreaming() was called. ### function close ```cpp SENSORS_ERROR_CODE close() ``` Closes the Sensors instance, releasing all resources and cameras. **Return**: [SENSORS_ERROR_CODE::SUCCESS] if successful. ### function Sensors ```cpp Sensors( const Sensors & ) =delete ``` The Sensors object cannot be copied. Therefore, its copy constructor is disabled. ### function operator= ```cpp Sensors & operator=( const Sensors & ) =delete ``` The Sensors object cannot be copied. Therefore, its copy assignment operator is disabled. ### function getSensorList ```cpp static SensorList getSensorList() ``` List all the connected sensor devices (cameras and lidars) with their associated information. **Return**: A SensorList containing device properties for each sensor type. **Warning**: As this method returns std::vectors, it is only safe to use in Release or ReleaseWithDebugInfos mode (not Debug). This is due to a known compatibility issue between release (the SDK) and debug (your app) implementations of std::vector. This method aggregates results from: * sl::Camera::getDeviceList() for ZED stereo cameras * sl::CameraOne::getDeviceList() for ZED One cameras * sl::Lidar::getDeviceList() for Lidar devices ### function getStreamingSensorList ```cpp static StreamingSensorList getStreamingSensorList() ``` List all the streaming sensor devices (cameras and lidars) with their associated information. **Return**: A StreamingSensorList containing streaming properties for each sensor type. **Warning**: * As this method returns std::vectors, it is only safe to use in Release or ReleaseWithDebugInfos mode (not Debug). This is due to a known compatibility issue between release (the SDK) and debug (your app) implementations of std::vector. * This method takes around 2 seconds to make sure all network information has been captured. Make sure to run this method in a thread. This method aggregates results from: * sl::Camera::getStreamingDeviceList() for ZED stereo cameras * sl::CameraOne::getStreamingDeviceList() for ZED One cameras * sl::Lidar::getStreamingDeviceList() for Lidar devices --- # sl::String **Module:** **Core Module** Class defining a string. `#include ` ## Public Functions Documentation ### function String ```cpp String() ``` Default constructor. ### function ~String ```cpp ~String() ``` Default destructor. ### function String ```cpp String( const String & str ) ``` Copy constructor. ### function String ```cpp String( const char * data ) ``` Constructor. ### function set ```cpp void set( const char * data ) ``` Sets the value of the sl::String. ### function get ```cpp const char * get() const ``` Returns the value of the sl::String. ### function empty ```cpp bool empty() const ``` Checks if the sl::String is empty. ### function operator= ```cpp String & operator=( const String & str1 ) ``` Copy the value of another sl::String. ### function operator= ```cpp String & operator=( const char * data ) ``` Copy the value of a char*. ### function operator= ```cpp String & operator=( const std::string & data ) ``` Copy the value of a std::string. ### function operator const char * ```cpp inline operator const char *() const ``` Convert the sl::String into a char*. ### function operator bool ```cpp inline explicit operator bool() const ``` Convert the sl::String into a bool. ### function c_str ```cpp const char * c_str() const ``` Returns the sl::String as a char*. ### function size ```cpp size_t size() const ``` Returns the size of the sl::String. ### function clear ```cpp void clear() ``` Empties the sl::String. ### function operator== ```cpp bool operator==( const String & s ) const ``` Checks that the value of the current sl::String is equal to the value of another sl::String. ### function operator!= ```cpp bool operator!=( const String & s ) const ``` Checks that the value of the current sl::String is different to the value of another sl::String. ### function operator== ```cpp bool operator==( const std::string & s ) const ``` Checks that the value of the current sl::String is equal to the value of another sl::String. ### function operator!= ```cpp bool operator!=( const std::string & s ) const ``` Checks that the value of the current sl::String is different to the value of another sl::String. ### function operator< ```cpp bool operator<( const String & s ) const ``` Checks if the value of the current sl::String is lexicographically less than the value of another sl::String. **Parameters**: * **s** The sl::String to compare with the current sl::String. **Return**: `true` if the current sl::String is lexicographically less than the other sl::String, otherwise `false`. ### function operator> ```cpp bool operator>( const String & s ) const ``` Checks if the value of the current sl::String is lexicographically greater than the value of another sl::String. **Parameters**: * **s** The sl::String to compare with the current sl::String. **Return**: `true` if the current sl::String is lexicographically greater than the other sl::String, otherwise `false`. ### function operator<= ```cpp bool operator<=( const String & s ) const ``` ### function operator>= ```cpp bool operator>=( const String & s ) const ``` --- # sl::Tensor **Module:** **Core Module** Class representing a multi-dimensional array (Tensor), typically used for deep learning inference. More... `#include ` Inherits from Mat ## Additional inherited members **Public Functions inherited from Mat** | | Name | | -------------- | -------------- | | | **Mat**()
Default constructor. | | | **Mat**(size_t width, size_t height, MAT_TYPE mat_type, MEM memory_type =[MEM::CPU])
Constructor. | | | **Mat**(size_t width, size_t height, MAT_TYPE mat_type, sl::uchar1 * ptr, size_t step, MEM memory_type =[MEM::CPU])
Constructor from an existing data pointer. | | | **Mat**(size_t width, size_t height, MAT_TYPE mat_type, sl::uchar1 * ptr_cpu, size_t step_cpu, sl::uchar1 * ptr_gpu, size_t step_gpu)
Constructor from two existing data pointers, CPU and GPU. | | | **Mat**(Resolution resolution, MAT_TYPE mat_type, MEM memory_type =[MEM::CPU])
Constructor from an sl::Resolution. | | | **Mat**(Resolution resolution, MAT_TYPE mat_type, sl::uchar1 * ptr, size_t step, MEM memory_type =[MEM::CPU])
Constructor from an existing data pointer. | | | **Mat**(Resolution resolution, MAT_TYPE mat_type, sl::uchar1 * ptr_cpu, size_t step_cpu, sl::uchar1 * ptr_gpu, size_t step_gpu)
Constructor from two existing data pointers, CPU and GPU. | | | **Mat**(const Mat & mat)
Copy constructor (shallow copy). | | virtual | **~Mat**()
Destructor. | | Mat & | **operator=**(const Mat & that)
Performs a shallow copy. | ## Detailed Description ```cpp class sl::Tensor; ``` Class representing a multi-dimensional array (Tensor), typically used for deep learning inference. **Note**: It inherits from Mat. ## Public Functions Documentation ### function Tensor ```cpp Tensor( const TensorParameters & params ={} ) ``` Default constructor. **Parameters**: * **params** : Parameters defining the Tensor creation and pre-processing. ### function Tensor ```cpp Tensor( const Tensor & tensor ) ``` Copy constructor (shallow copy). **Parameters**: * **tensor** : The sl::Tensor to copy. ### function alloc ```cpp void alloc( const TensorParameters & params ) ``` Allocates the Tensor memory. **Parameters**: * **params** : Parameters defining the Tensor creation. ### function getDims ```cpp std::vector< size_t > getDims() const ``` Returns the dimensions of the Tensor. **Return**: A vector containing the size of each dimension (e.g., {Batch, Channels, Height, Width} for NCHW). ### function getElementCount ```cpp size_t getElementCount() const ``` Returns the total number of elements in the Tensor. **Return**: The product of all dimensions. ### function getParameters ```cpp TensorParameters getParameters() const ``` Returns the parameters used to create or define the Tensor. **Return**: The TensorParameters associated with this Tensor. ### function alloc ```cpp void alloc( size_t width, size_t height, MAT_TYPE mat_type, MEM memory_type =MEM::CPU ) ``` Allocates the sl::Mat memory. **Parameters**: * **width** : Width of the matrix in pixels. * **height** : Height of the matrix in pixels. * **mat_type** : Type of the matrix (sl::MAT_TYPE::F32_C1, sl::MAT_TYPE::U8_C4, etc.). * **memory_type** : Where the buffer will be stored (sl::MEM::CPU and/or sl::MEM::GPU). **Warning**: It erases previously allocated memory. ### function alloc ```cpp void alloc( Resolution resolution, MAT_TYPE mat_type, MEM memory_type =MEM::CPU ) ``` Allocates the sl::Mat memory. **Parameters**: * **resolution** : Size of the matrix in pixels. * **mat_type** : Type of the matrix (sl::MAT_TYPE::F32_C1, sl::MAT_TYPE::U8_C4, etc.). * **memory_type** : Where the buffer will be stored (sl::MEM::CPU and/or sl::MEM::GPU). **Warning**: It erases previously allocated memory. ### function free ```cpp void free( MEM memory_type =MEM::BOTH ) ``` Free the owned memory. **Parameters**: * **memory_type** : Specifies whether you want to free the sl::MEM::CPU and/or sl::MEM::GPU memory. ### function updateCPUfromGPU ```cpp ERROR_CODE updateCPUfromGPU( cudaStream_t stream =0 ) ``` Downloads data from DEVICE (GPU) to HOST (CPU), if possible. **Parameters**: * **stream** : Specifies the GPU stream to be used to enable asynchronous overlapping. Default: 0 (synchronous) **Return**: sl::ERROR_CODE::SUCCESS if everything went well, sl::ERROR_CODE::FAILURE otherwise. **Note**: * If no CPU or GPU memory are available for this sl::Mat, some are directly allocated. * If verbose is set to true, you have information in case of failure. ### function updateGPUfromCPU ```cpp ERROR_CODE updateGPUfromCPU( cudaStream_t stream =0, int GPU_id =0 ) ``` Uploads data from HOST (CPU) to DEVICE (GPU), if possible. **Parameters**: * **stream** : Specifies the GPU stream to be used to enable asynchronous overlapping. Default: 0 (synchronous) * **GPU_id** : Specifies the GPU id to be used. Default: 0 (first GPU). **Return**: sl::ERROR_CODE::SUCCESS if everything went well, sl::ERROR_CODE::FAILURE otherwise. **Note**: * If no CPU or GPU memory are available for this sl::Mat, some are directly allocated. * If verbose is set to true, you have information in case of failure. ### function copyTo ```cpp ERROR_CODE copyTo( Mat & dst, COPY_TYPE cpyType =COPY_TYPE::CPU_CPU, cudaStream_t stream =0 ) const ``` Copies data an other sl::Mat (deep copy). **Parameters**: * **dst** : sl::Mat where the data will be copied. * **cpyType** : Specifies the memory that will be used for the copy. * **stream** : Specifies the GPU stream to be used to enable asynchronous overlapping. Default: 0 (synchronous) **Return**: sl::ERROR_CODE::SUCCESS if everything went well, sl::ERROR_CODE::FAILURE otherwise. **Note**: If the destination is not allocated or or doesn't have a compatible sl::MAT_TYPE or sl::Resolution, current memory is freed and new memory is directly allocated. ### function setFrom ```cpp ERROR_CODE setFrom( const Mat & src, COPY_TYPE cpyType =COPY_TYPE::CPU_CPU, cudaStream_t stream =0 ) ``` Copies data from an other sl::Mat (deep copy). **Parameters**: * **src** : sl::Mat where the data will be copied from. * **cpyType** : Specifies the memory that will be used for the copy. * **stream** : Specifies the GPU stream to be used to enable asynchronous overlapping. Default: 0 (synchronous) **Return**: sl::ERROR_CODE::SUCCESS if everything went well, sl::ERROR_CODE::FAILURE otherwise. **Note**: If the destination is not allocated or or doesn't have a compatible sl::MAT_TYPE or sl::Resolution, current memory is freed and new memory is directly allocated. ### function read ```cpp ERROR_CODE read( const String & filePath ) ``` Reads an image from a file. **Parameters**: * **filePath** : Path of the file to read (including the name and extension). **Return**: sl::ERROR_CODE::SUCCESS if everything went well, sl::ERROR_CODE::FAILURE otherwise. **Note**: This method only support images such as JPG or PNG, and can't load float format such as PCD, PLY, etc. ### function write ```cpp ERROR_CODE write( const String & filePath, sl::MEM memory_type =sl::MEM::CPU, int compression_level =-1 ) ``` Writes the sl::Mat (only if sl::MEM::CPU is available) into a file defined by its extension. **Parameters**: * **filePath** : Path of the file to write in (including the name and extension). * **memory_type** : Memory type (CPU or GPU) of the sl::Mat. * **compression_level** : Level of compression between 0 (lowest compression == highest size == highest quality(jpg)) and 100 (highest compression == lowest size == lowest quality(jpg)). **Return**: sl::ERROR_CODE::SUCCESS if everything went well, sl::ERROR_CODE::FAILURE otherwise. **Note**: * Specific/default value for compression_level = -1 : This will set the default quality for PNG(30) or JPEG(5). * **compression_level** is only supported for U8_Cx sl::MAT_TYPE. * Supported sl::MAT_TYPE are: * sl::MAT_TYPE::F32_C1 for PNG/PFM/PGM * sl::MAT_TYPE::F32_C3 for PCD/PLY/VTK/XYZ * sl::MAT_TYPE::F32_C4 for PCD/PLY/VTK/WYZ * sl::MAT_TYPE::U8_C1 for PNG/JPG * sl::MAT_TYPE::U8_C3 for PNG/JPG * sl::MAT_TYPE::U8_C4 for PNG/JPG ### function setTo ```cpp template ERROR_CODE setTo( const T & value, const sl::MEM memory_type =MEM::CPU, cudaStream_t stream =0 ) ``` Fills the sl::Mat with the given value. **Parameters**: * **value** : Value to be copied all over the matrix. * **memory_type** : Which buffer to fill, CPU and/or GPU. * **stream** : a cuda stream to put the compute to (default 0). **Return**: sl::ERROR_CODE::SUCCESS if everything went well, sl::ERROR_CODE::FAILURE otherwise. **Note**: This method is templated for sl::uchar1, sl::uchar2, sl::uchar3, sl::uchar4, sl::float1, sl::float2, sl::float3, sl::float4, sl::char4, sl::ushort1. This method overwrites all the matrix. ### function setValue ```cpp template ERROR_CODE setValue( const size_t x, const size_t y, const N & value, const sl::MEM memory_type =MEM::CPU ) ``` Sets a value to a specific point in the matrix. **Parameters**: * **x** : Column of the point to change. * **y** : Row of the point to change. * **value** : Value to be set. * **memory_type** : Which memory will be updated. **Return**: sl::ERROR_CODE::SUCCESS if everything went well, sl::ERROR_CODE::FAILURE otherwise. **Note**: This method is templated for sl::uchar1, sl::uchar2, sl::uchar3, sl::uchar4, sl::float1, sl::float2, sl::float3, sl::float4, sl::char4, sl::ushort1. **Warning**: Not efficient for sl::MEM::GPU, use it on sparse data. ### function getValue ```cpp template ERROR_CODE getValue( const size_t x, const size_t y, N * value, const MEM memory_type =MEM::CPU ) const ``` Get the value of a specific point in the matrix. **Parameters**: * **x** : Column of the point to get the value from. * **y** : Row of the point to get the value from. * **value** : Pointer to the value to be filled. * **memory_type** : Which memory should be read. **Return**: sl::ERROR_CODE::SUCCESS if everything went well, sl::ERROR_CODE::FAILURE otherwise. **Note**: This method is templated for sl::uchar1, sl::uchar2, sl::uchar3, sl::uchar4, sl::float1, sl::float2, sl::float3, sl::float4, sl::char4, sl::ushort1. **Warning**: Not efficient for sl::MEM::GPU, use it on sparse data. ### function getWidth ```cpp inline size_t getWidth() const ``` Returns the width of the matrix. **Return**: Width of the matrix in pixels. ### function getHeight ```cpp inline size_t getHeight() const ``` Returns the height of the matrix. **Return**: Height of the matrix in pixels. ### function getResolution ```cpp inline const Resolution & getResolution() const ``` Returns the resolution (width and height) of the matrix. **Return**: Resolution of the matrix in pixels. ### function getResolution ```cpp inline Resolution getResolution() ``` Returns the resolution (width and height) of the matrix. **Return**: Resolution of the matrix in pixels. ### function getResolution ```cpp void getResolution() const =delete ``` Prevent method from being called by temporaries (such as rvalue) ### function getChannels ```cpp inline size_t getChannels() const ``` Returns the number of values stored in one pixel. **Return**: Number of values in a pixel. ### function getDataType ```cpp inline MAT_TYPE getDataType() const ``` Returns the format of the matrix. **Return**: Format of the current sl::Mat. ### function getMemoryType ```cpp inline MEM getMemoryType() const ``` Returns the type of memory (CPU and/or GPU). **Return**: Type of allocated memory. ### function getPtr ```cpp template N * getPtr( const MEM memory_type =MEM::CPU ) const ``` Returns the CPU or GPU data pointer. **Parameters**: * **memory_type** : Specifies whether you want sl::MEM::CPU or sl::MEM::GPU. **Return**: The pointer of the Mat data. ### function getStepBytes ```cpp size_t getStepBytes( const MEM memory_type =MEM::CPU ) const ``` Returns the memory step in bytes (size of one pixel row). **Parameters**: * **memory_type** : Specifies whether you want sl::MEM::CPU or sl::MEM::GPU step. **Return**: The step in bytes of the specified memory. ### function getStep ```cpp template inline size_t getStep( const MEM memory_type =MEM::CPU ) const ``` Returns the memory step in number of elements (size in one pixel row). **Parameters**: * **memory_type** : Specifies whether you want sl::MEM::CPU or sl::MEM::GPU step. **Return**: The step in number of elements. ### function getStep ```cpp inline size_t getStep( MEM memory_type =MEM::CPU ) const ``` Returns the memory step in number of elements (size in one pixel row). **Parameters**: * **memory_type** : Specifies whether you want sl::MEM::CPU or sl::MEM::GPU step. **Return**: The step in number of elements. ### function getPixelBytes ```cpp inline size_t getPixelBytes() const ``` Returns the size of one pixel in bytes. **Return**: Size of a pixel in bytes. ### function getWidthBytes ```cpp inline size_t getWidthBytes() const ``` Returns the size of a row in bytes. **Return**: Size of a row in bytes. ### function getInfos ```cpp String getInfos() const ``` Returns the information about the sl::Mat into a sl::String. **Return**: String containing the sl::Mat information. ### function isInit ```cpp inline bool isInit() const ``` Returns whether the sl::Mat is initialized or not. **Return**: True if current sl::Mat has been allocated (by the constructor or therefore). ### function isMemoryOwner ```cpp inline bool isMemoryOwner() const ``` Returns whether the sl::Mat is the owner of the memory it accesses. **Return**: True if the sl::Mat is owning its memory, else false. If not, the memory won't be freed if the sl::Mat is destroyed. ### function clone ```cpp ERROR_CODE clone( const Mat & src ) ``` Duplicates a sl::Mat by copy (deep copy). **Parameters**: * **src** : Reference of the sl::Mat to copy. This method copies the data array(s) and it marks the new sl::Mat as the memory owner. ### function move ```cpp ERROR_CODE move( Mat & dst ) ``` Moves the data of the sl::Mat to another sl::Mat. **Parameters**: * **dst** : Reference to the sl::Mat to move to. **Note**: : The current sl::Mat is then no more usable since its loose its attributes. This method gives the attribute of the current s::Mat to the specified one. (No copy.) ### function convertColor ```cpp ERROR_CODE convertColor( sl::MEM memory =sl::MEM::CPU, cudaStream_t stream =0, bool swap_RB_channels =true ) ``` Convert the color channels of the Mat (RGB<->BGR or RGBA<->BGRA) This methods works only on 8U_C4 or 8U_C3. ### function convertColor ```cpp static ERROR_CODE convertColor( Mat & mat1, Mat & mat2, bool swap_RB_channels, bool remove_alpha_channels, sl::MEM memory =sl::MEM::CPU, cudaStream_t stream =0 ) ``` 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. ### function swap ```cpp static void swap( Mat & mat1, Mat & mat2 ) ``` Swaps the content of the provided sl::Mat (only swaps the pointers, no data copy). **Parameters**: * **mat1** : First matrix to swap. * **mat2** : Second matrix to swap. This method swaps the pointers of the given sl::Mat. ## Protected Functions Documentation ### function ref ```cpp void ref( const Mat & mat ) ``` ## Public Attributes Documentation ### variable name ```cpp String name; ``` Variable used in verbose mode to indicate which sl::Mat is printing informations. Default set to "n/a" to avoid empty string if not filled. ### variable verbose ```cpp bool verbose = false; ``` Whether the sl::Mat can display informations. ### variable timestamp ```cpp Timestamp timestamp = 0; ``` Timestamp of the last manipulation of the data of the matrix by a method/function. ## Protected Attributes Documentation ### variable size ```cpp Resolution size; ``` ### variable channels ```cpp size_t channels = 0; ``` ### variable step_gpu ```cpp size_t step_gpu = 0; ``` ### variable step_cpu ```cpp size_t step_cpu = 0; ``` ### variable pixel_bytes ```cpp size_t pixel_bytes = 0; ``` ### variable data_type ```cpp MAT_TYPE data_type = MAT_TYPE::U8_C1; ``` ### variable mem_type ```cpp MEM mem_type = MEM::CPU; ``` ### variable ptr_cpu ```cpp std::shared_ptr< uchar1 > ptr_cpu = NULL; ``` ### variable ptr_gpu ```cpp std::shared_ptr< uchar1 > ptr_gpu = NULL; ``` ### variable init ```cpp bool init = false; ``` ### variable memory_owner ```cpp bool memory_owner = false; ``` --- # sl::Transform **Module:** **Positional Tracking Module** Class representing a transformation (translation and rotation) for the positional tracking module. More... `#include ` Inherits from Matrix4f ## Additional inherited members **Public Functions inherited from Matrix4f** | | Name | | -------------- | -------------- | | | **Matrix4f**()
Default constructor. | | virtual | **~Matrix4f**() =default | | | **Matrix4f**(float data[])
Copy constructor (deep copy). | | | **Matrix4f**(const Matrix4f & mat)
Copy constructor (deep copy). | | | **Matrix4f**(Matrix4f && mat)
Move constructor. | ## Detailed Description ```cpp class sl::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. ## Public Functions Documentation ### function Transform ```cpp Transform() ``` Default constructor. ### function ~Transform ```cpp virtual ~Transform() =default ``` ### function Transform ```cpp Transform( const Transform & motion ) ``` Copy constructor (deep copy). **Parameters**: * **motion** : sl::Transform to copy. ### function Transform ```cpp Transform( const Matrix4f & mat ) ``` Copy constructor (deep copy). **Parameters**: * **mat** : sl::Matrix4f to copy. ### function Transform ```cpp Transform( const Rotation & rotation, const Translation & translation ) ``` Constructor from an sl::Rotation and a sl::Translation. **Parameters**: * **rotation** : sl::Rotation to copy. * **translation** : sl::Translation to copy. ### function Transform ```cpp Transform( const Orientation & orientation, const Translation & translation ) ``` Constructor from an sl::Orientation and a sl::Translation. **Parameters**: * **orientation** : sl::Orientation to copy. * **translation** : sl::Translation to copy. ### function Transform ```cpp Transform( Transform && motion ) ``` Move constructor. **Parameters**: * **motion** : sl::Transform to move. ### function operator= ```cpp Transform & operator=( const Transform & motion ) ``` Copy assignment operator. ### function operator= ```cpp Transform & operator=( Transform && motion ) ``` Move assignment operator. ### function operator= ```cpp Transform & operator=( const Matrix4f & mat ) ``` Copy assignment operator from Matrix4f. ### function setRotationMatrix ```cpp void setRotationMatrix( const Rotation & rotation ) ``` Sets the rotation component of the current sl::Transform from an sl::Rotation. **Parameters**: * **rotation** : sl::Rotation to be used. ### function getRotationMatrix ```cpp Rotation getRotationMatrix() const ``` 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. Not references. ### function setTranslation ```cpp void setTranslation( const Translation & translation ) ``` Sets the translation component of the current sl::Transform from an sl::Translation. **Parameters**: * **translation** : sl::Translation to be used. ### function getTranslation ```cpp Translation getTranslation() const ``` 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. Not references. ### function setOrientation ```cpp void setOrientation( const Orientation & orientation ) ``` Sets the orientation component of the current sl::Transform from an sl::Orientation. **Parameters**: * **orientation** : sl::Orientation to be used. ### function getOrientation ```cpp Orientation getOrientation() const ``` 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. ### function getRotationVector ```cpp float3 getRotationVector() const ``` Returns the 3x1 rotation vector obtained from 3x3 rotation matrix using Rodrigues formula. **Return**: Rotation vector created from the sl::Transform values. ### function setRotationVector ```cpp void setRotationVector( const float3 & vec_rot ) ``` Sets the rotation component of the sl::Transform with a 3x1 rotation vector (using Rodrigues' transformation). **Parameters**: * **vec_rot** : Vector containing the rotation value for each axis `(rx, ry, rz)`. ### function getEulerAngles ```cpp float3 getEulerAngles( bool radian =true ) const ``` Converts the rotation component of the sl::Transform into Euler angles. **Parameters**: * **radian** : Whether the angle will be returned in radian or degree. **Return**: Euler angles created from the sl::Transform values as a sl::float3 representing the rotations around the X, Y and Z axes using YZX convention. ### function setEulerAngles ```cpp void setEulerAngles( const float3 & euler_angles, bool radian =true ) ``` Sets the rotation component of the sl::Transform from Euler angles. **Parameters**: * **euler_angles** : Euler angles (as a sl::float3) to update the sl::Transform. * **radian** : Whether the angle is in radian or degree. ### function operator* ```cpp Matrix4f operator*( const Matrix4f & mat ) const ``` Gives the result of the multiplication between two sl::Matrix4f. ### function operator* ```cpp Matrix4f operator*( const Vector4< float > & vect ) const ``` Gives the result of the multiplication between a sl::Matrix4f and a sl::float4. ### function operator* ```cpp Matrix4f operator*( const float & scalar ) const ``` Gives the result of the multiplication between a sl::Matrix4f and a scalar. ### function operator+ ```cpp Matrix4f operator+( const Matrix4f & mat ) const ``` Gives the result of the addition between two sl::Matrix4f. ### function operator+ ```cpp Matrix4f operator+( const float & scalar ) const ``` Gives the result of the addition between a sl::Matrix4f and a scalar. ### function operator- ```cpp Matrix4f operator-( const Matrix4f & mat ) const ``` Gives the result of the subtraction between two sl::Matrix4f. ### function operator- ```cpp Matrix4f operator-( const float & scalar ) const ``` Gives the result of the subtraction between a sl::Matrix4f and a scalar. ### function operator== ```cpp bool operator==( const Matrix4f & mat ) const ``` Tests two sl::Matrix4f equality. ### function operator!= ```cpp bool operator!=( const Matrix4f & mat ) const ``` Tests two sl::Matrix4f inequality. ### function operator() ```cpp float & operator()( int const u, int const v ) ``` Gets access to a specific point in the sl::Matrix4f (read/write). **Parameters**: * **u** : Row to get the value from. * **v** : Column to get the value from. **Return**: The value at the u, v coordinates. ### function operator() ```cpp float operator()( int const u, int const v ) const ``` Gets access to a specific point in the sl::Matrix4f (read). **Parameters**: * **u** : Row to get the value from. * **v** : Column to get the value from. **Return**: The value at the u, v coordinates. ### function inverse ```cpp ERROR_CODE inverse() ``` 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). ### function transpose ```cpp void transpose() ``` Sets the sl::Matrix4f to its transpose. ### function setIdentity ```cpp void setIdentity() ``` Sets the sl::Matrix4f to identity. ### function setZeros ```cpp void setZeros() ``` Sets the sl::Matrix4f to zero. ### function setSubMatrix3f ```cpp ERROR_CODE setSubMatrix3f( Matrix3f input, int row =0, int column =0 ) ``` Sets a sl::Matrix3f inside the sl::Matrix4f. **Parameters**: * **input** : Sub-matrix to put inside the sl::Matrix4f. * **row** : Index of the row to start the 3x3 block. Must be 0 or 1. * **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. **Note**: Can be used to set the rotation matrix when the sl::Matrix4f is a pose or an isometric matrix. ### function setSubVector3f ```cpp ERROR_CODE setSubVector3f( Vector3< float > input, int column =3 ) ``` Sets a sl::Vector3 inside the sl::Matrix4f at the specified column index. **Parameters**: * **input** : Sub-vector to put inside the sl::Matrix4f. * **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. **Note**: Can be used to set the translation/position matrix when the sl::Matrix4f is a pose or an isometry. ### function setSubVector4f ```cpp ERROR_CODE setSubVector4f( Vector4< float > input, int column =3 ) ``` Sets a sl::Vector4 inside the sl::Matrix4f at the specified column index. **Parameters**: * **input** : Sub-vector to put inside the sl::Matrix4f. * **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. **Note**: Can be used to set the translation/position matrix when the sl::Matrix4f is a pose or an isometry. ### function getInfos ```cpp String getInfos() const ``` Returns the components of the sl::Matrix4f in a sl::String. **Return**: A sl::String containing the components of the current sl::Matrix4f. ### function inverse ```cpp static Matrix4f inverse( const Matrix4f & mat ) ``` Creates the inverse of a sl::Matrix4f. **Parameters**: * **mat** : sl::Matrix4f to compute the inverse from. **Return**: The inverse of the sl::Matrix4f given as input. ### function transpose ```cpp static Matrix4f transpose( const Matrix4f & mat ) ``` Creates the transpose of a sl::Matrix4f. **Parameters**: * **mat** : sl::Matrix4f to compute the transpose from. **Return**: The transpose of the sl::Matrix4f given as input. ### function identity ```cpp static Matrix4f identity() ``` Creates an identity sl::Matrix4f. **Return**: A sl::Matrix4f set to identity. ### function zeros ```cpp static Matrix4f zeros() ``` Creates a sl::Matrix4f filled with zeros. **Return**: A sl::Matrix4f filled with zero. ## Public Attributes Documentation ### variable matrix_name ```cpp String matrix_name; ``` Name of the matrix (optional). --- # sl::Translation **Module:** **Positional Tracking Module** Class representing a translation for the positional tracking module. More... `#include ` Inherits from Vector3< float > ## Additional inherited members **Public Functions inherited from Vector3< float >** | | Name | | -------------- | -------------- | | _FCT_CPU_GPU_ | **Vector3**()
Default constructor. | | _FCT_CPU_GPU_ | **Vector3**(const T & t)
Constructor. | | _FCT_CPU_GPU_ | **Vector3**(const T * tp)
Constructor. | | _FCT_CPU_GPU_ | **Vector3**(const T v0, const T v1, const T v2)
Constructor. | | _FCT_CPU_GPU_ | **Vector3**(const Vector3< T > & vec)
Copy constructor. | | _FCT_CPU_GPU_ | **Vector3**(const Vector2< T > & vec, const T d =0)
Constructor. | | _FCT_CPU_GPU_ | **Vector3**(const Vector4< T > & vec)
Constructor. | | _FCT_CPU_GPU_ Vector3< T > & | **operator=**(const Vector4< T > & other)
Test the equality of the sl::Vector3 with the first three components of a sl::Vector4. | **Friends inherited from Vector3< float >** | | Name | | -------------- | -------------- | | _FCT_CPU_GPU_ friend Vector3< T > & | **operator+=**(Vector3< T > & itself, T d) | | _FCT_CPU_GPU_ friend Vector3< T > & | **operator+=**(Vector3< T > & itself, const Vector3< T > & b) | | _FCT_CPU_GPU_ friend Vector3< T > & | **operator-=**(Vector3< T > & itself, T d) | | _FCT_CPU_GPU_ friend Vector3< T > & | **operator-=**(Vector3< T > & itself, const Vector3< T > & b) | | _FCT_CPU_GPU_ friend Vector3< T > & | **operator*=**(Vector3< T > & itself, T d) | | _FCT_CPU_GPU_ friend Vector3< T > & | **operator*=**(Vector3< T > & itself, const Vector3< T > & b) | | _FCT_CPU_GPU_ friend Vector3< T > & | **operator*=**(Vector3< T > & itself, const Matrix3f & b) | | _FCT_CPU_GPU_ friend Vector3< T > & | **operator/=**(Vector3< T > & itself, T d) | | _FCT_CPU_GPU_ friend Vector3< T > & | **operator/=**(Vector3< T > & itself, const Vector3< T > & b) | | _FCT_CPU_GPU_ friend bool | **operator==**(const Vector3< T > & itself, const Vector3< T > & b) | | _FCT_CPU_GPU_ friend Vector3< T > | **operator+**(const Vector3< T > & a, const Vector3< T > & b) | | _FCT_CPU_GPU_ friend Vector3< T > | **operator-**(const Vector3< T > & a, const Vector3< T > & b) | | _FCT_CPU_GPU_ friend Vector3< T > | **operator/**(const Vector3< T > & a, T b) | | _FCT_CPU_GPU_ friend Vector3< T > | **operator/**(const Vector3< T > & a, const Vector3< T > & b) | ## Detailed Description ```cpp class sl::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 't' ptr or by element name as : tx, ty, tz <-> | 0 1 2 | ## Public Functions Documentation ### function Translation ```cpp Translation() ``` Default constructor. Creates a null translation. ### function Translation ```cpp Translation( const Translation & translation ) ``` Copy constructor (deep copy). **Parameters**: * **translation** : sl::Translation to copy. ### function Translation ```cpp Translation( float t1, float t2, float t3 ) ``` Constructor. **Parameters**: * **t1** : x component of the translation. * **t2** : y component of the translation. * **t3** : z component of the translation. ### function Translation ```cpp Translation( float3 in ) ``` Constructor from an sl::float3. **Parameters**: * **in** : sl::float3 to copy. ### function operator* ```cpp Translation operator*( const Orientation & mat ) const ``` Multiplication operator by an Orientation. **Parameters**: * **mat** : Orientation. **Return**: The current Translation after being multiplied by the orientation. ### function normalize ```cpp void normalize() ``` Normalizes the current sl::Translation. ### function operator() ```cpp float & operator()( int x ) ``` Gets the value at specific position in the sl::Translation. **Parameters**: * **x** : Position of the value. **Return**: Value at the x position. ### function size ```cpp inline _FCT_CPU_GPU_ int size() const ``` Return the size of the sl::Vector3. **Return**: 3 ### function ptr ```cpp inline _FCT_CPU_GPU_ const float * ptr() const ``` Returns a pointer of the first component. ### function setValues ```cpp inline _FCT_CPU_GPU_ Vector3< float > & setValues( const float * vals ) ``` Sets the components of the sl::Vector3 to the values of the argument. ### function operator[] ```cpp inline _FCT_CPU_GPU_ float & operator[]( const unsigned int i ) ``` Returns the **i-th** component. ### function operator[] ```cpp inline _FCT_CPU_GPU_ const float & operator[]( const unsigned int i ) const ``` Returns the **i-th** component. ### function operator[] ```cpp _FCT_CPU_GPU_ void operator[]( const unsigned int i ) =delete ``` Prevent operator from being called by temporaries (such as rvalue) ### function norm ```cpp inline _FCT_CPU_GPU_ float norm() ``` Returns the norm of the sl::Vector3. ### function square ```cpp inline _FCT_CPU_GPU_ float square() ``` Returns the squared norm of the sl::Vector3. ### function sum ```cpp inline _FCT_CPU_GPU_ float sum() ``` Returns the sum of the components of the sl::Vector3. ### function normalize ```cpp static Translation normalize( const Translation & tr ) ``` Gets the normalized sl::Translation of a given sl::Translation. **Parameters**: * **tr** : sl::Translation to be get the normalized translation from. **Return**: Another sl::Translation object equal to **tr**.normalize(). ### function dot ```cpp static inline _FCT_CPU_GPU_ float dot( const Vector3< float > & a, const Vector3< float > & b ) ``` Returns the dot product of two sl::Vector3. ### function distance ```cpp static inline _FCT_CPU_GPU_ float distance( const Vector3< float > & a, const Vector3< float > & b ) ``` Returns the distance between two sl::Vector3. ### function cross ```cpp static inline _FCT_CPU_GPU_ Vector3< float > cross( const Vector3< float > & a, const Vector3< float > & b ) ``` Returns the cross product between two sl::Vector3. --- # sl::UTM **Module:** **Fusion Module** Represents a world position in UTM format. `#include ` ## Public Attributes Documentation ### variable northing ```cpp double northing; ``` Northing coordinate. ### variable easting ```cpp double easting; ``` Easting coordinate. ### variable gamma ```cpp double gamma; ``` Gamma coordinate. ### variable UTMZone ```cpp std::string UTMZone; ``` UTMZone of the coordinate. --- # sl::Vector2 **Module:** **Core Module** Class representing a 2-dimensional vector for both CPU and GPU. More... `#include ` ## Detailed Description ```cpp template class sl::Vector2; ``` Class representing a 2-dimensional vector for both CPU and GPU. ## Public Functions Documentation ### function size ```cpp inline _FCT_CPU_GPU_ int size() const ``` Return the size of the sl::Vector2. **Return**: 2 ### function Vector2 ```cpp inline _FCT_CPU_GPU_ Vector2() ``` Default constructor. Initialize the sl::Vector2 to 0. ### function Vector2 ```cpp inline _FCT_CPU_GPU_ Vector2( const T & t ) ``` Constructor. Initialize the sl::Vector2 to ( **t**, **t** ). ### function Vector2 ```cpp inline _FCT_CPU_GPU_ Vector2( const T * tp ) ``` Constructor. Initialize the sl::Vector2 with the component of the argument. ### function Vector2 ```cpp inline _FCT_CPU_GPU_ Vector2( const T v0, const T v1 ) ``` Constructor. Initialize the sl::Vector2 to ( **v0**, **v1** ). ### function Vector2 ```cpp inline _FCT_CPU_GPU_ Vector2( const Vector2< T > & vec ) ``` Copy constructor. Initialize the sl::Vector2 by copying another sl::Vector2. ### function ptr ```cpp inline _FCT_CPU_GPU_ const T * ptr() const ``` Returns a pointer of the first component. ### function setValues ```cpp inline _FCT_CPU_GPU_ Vector2 & setValues( const T * vals ) ``` Sets the components of the sl::Vector2 to the values of the argument. ### function operator[] ```cpp inline _FCT_CPU_GPU_ T & operator[]( const unsigned int i ) ``` Returns the **i-th** component. ### function operator[] ```cpp inline _FCT_CPU_GPU_ const T & operator[]( const unsigned int i ) const ``` Returns the **i-th** component. ### function operator[] ```cpp template _FCT_CPU_GPU_ void operator[]( const unsigned int i ) =delete ``` Prevent operator from being called by temporaries (such as rvalue) ### function norm ```cpp inline _FCT_CPU_GPU_ float norm() ``` Returns the norm of the sl::Vector2. ### function square ```cpp inline _FCT_CPU_GPU_ float square() ``` Returns the squared norm of the sl::Vector2. ### function sum ```cpp inline _FCT_CPU_GPU_ float sum() ``` Returns the sum of the components of the sl::Vector2. ### function dot ```cpp static inline _FCT_CPU_GPU_ float dot( const Vector2< T > & a, const Vector2< T > & b ) ``` Returns the dot product of two sl::Vector2. ### function distance ```cpp static inline _FCT_CPU_GPU_ float distance( const Vector2< T > & a, const Vector2< T > & b ) ``` Returns the distance between two sl::Vector2. --- # sl::Vector3 **Module:** **Core Module** Class representing a 3-dimensional vector for both CPU and GPU. More... `#include ` ## Detailed Description ```cpp template class sl::Vector3; ``` Class representing a 3-dimensional vector for both CPU and GPU. ## Public Functions Documentation ### function size ```cpp inline _FCT_CPU_GPU_ int size() const ``` Return the size of the sl::Vector3. **Return**: 3 ### function Vector3 ```cpp inline _FCT_CPU_GPU_ Vector3() ``` Default constructor. Initialize the sl::Vector3 to 0. ### function Vector3 ```cpp inline _FCT_CPU_GPU_ Vector3( const T & t ) ``` Constructor. Initialize the sl::Vector3 to ( **t**, **t**, **t** ). ### function Vector3 ```cpp inline _FCT_CPU_GPU_ Vector3( const T * tp ) ``` Constructor. Initialize the sl::Vector3 with the component of the argument. ### function Vector3 ```cpp inline _FCT_CPU_GPU_ Vector3( const T v0, const T v1, const T v2 ) ``` Constructor. Initialize the sl::Vector3 to ( **v0**, **v1**, **v2** ). ### function Vector3 ```cpp inline _FCT_CPU_GPU_ Vector3( const Vector3< T > & vec ) ``` Copy constructor. Initialize the sl::Vector3 by copying another sl::Vector3. ### function Vector3 ```cpp inline _FCT_CPU_GPU_ Vector3( const Vector2< T > & vec, const T d =0 ) ``` Constructor. Initialize the sl::Vector3 with a sl::Vector2 and a scalar (for the third component). ### function Vector3 ```cpp inline _FCT_CPU_GPU_ Vector3( const Vector4< T > & vec ) ``` Constructor. Initialize the sl::Vector3 with the first three components of a sl::Vector4. ### function ptr ```cpp inline _FCT_CPU_GPU_ const T * ptr() const ``` Returns a pointer of the first component. ### function setValues ```cpp inline _FCT_CPU_GPU_ Vector3< T > & setValues( const T * vals ) ``` Sets the components of the sl::Vector3 to the values of the argument. ### function operator= ```cpp inline _FCT_CPU_GPU_ Vector3< T > & operator=( const Vector4< T > & other ) ``` Test the equality of the sl::Vector3 with the first three components of a sl::Vector4. ### function operator[] ```cpp inline _FCT_CPU_GPU_ T & operator[]( const unsigned int i ) ``` Returns the **i-th** component. ### function operator[] ```cpp inline _FCT_CPU_GPU_ const T & operator[]( const unsigned int i ) const ``` Returns the **i-th** component. ### function operator[] ```cpp template _FCT_CPU_GPU_ void operator[]( const unsigned int i ) =delete ``` Prevent operator from being called by temporaries (such as rvalue) ### function norm ```cpp inline _FCT_CPU_GPU_ float norm() ``` Returns the norm of the sl::Vector3. ### function square ```cpp inline _FCT_CPU_GPU_ float square() ``` Returns the squared norm of the sl::Vector3. ### function sum ```cpp inline _FCT_CPU_GPU_ float sum() ``` Returns the sum of the components of the sl::Vector3. ### function dot ```cpp static inline _FCT_CPU_GPU_ float dot( const Vector3< T > & a, const Vector3< T > & b ) ``` Returns the dot product of two sl::Vector3. ### function distance ```cpp static inline _FCT_CPU_GPU_ float distance( const Vector3< T > & a, const Vector3< T > & b ) ``` Returns the distance between two sl::Vector3. ### function cross ```cpp static inline _FCT_CPU_GPU_ Vector3< T > cross( const Vector3< T > & a, const Vector3< T > & b ) ``` Returns the cross product between two sl::Vector3. --- # sl::Vector4 **Module:** **Core Module** Class representing a 4-dimensional vector for both CPU and GPU. More... `#include ` ## Detailed Description ```cpp template class sl::Vector4; ``` Class representing a 4-dimensional vector for both CPU and GPU. ## Public Functions Documentation ### function size ```cpp inline _FCT_CPU_GPU_ int size() const ``` Return the size of the sl::Vector4. **Return**: 4 ### function Vector4 ```cpp inline _FCT_CPU_GPU_ Vector4() ``` Default constructor. Initialize the sl::Vector4 to 0. ### function Vector4 ```cpp inline _FCT_CPU_GPU_ Vector4( const T & t ) ``` Constructor. Initialize the sl::Vector4 to ( **t**, **t**, **t**, **t** ). ### function Vector4 ```cpp inline _FCT_CPU_GPU_ Vector4( const T * tp ) ``` Constructor. Initialize the sl::Vector4 with the component of the argument. ### function Vector4 ```cpp inline _FCT_CPU_GPU_ Vector4( const T v0, const T v1, const T v2, const T v3 ) ``` Constructor. Initialize the sl::Vector4 to ( **v0**, **v1**, **v2**, **v3** ). ### function Vector4 ```cpp inline _FCT_CPU_GPU_ Vector4( const Vector4< T > & vec ) ``` Copy constructor. Initialize the sl::Vector4 by copying another sl::Vector4. ### function Vector4 ```cpp inline _FCT_CPU_GPU_ Vector4( const Vector4< T > & vec, const T d ) ``` Constructor. Initialize the sl::Vector4 with the first three components of a sl::Vector4 and a scalar (for the forth component). ### function Vector4 ```cpp inline _FCT_CPU_GPU_ Vector4( const Vector3< T > & vec, const T d =0 ) ``` Constructor. Initialize the sl::Vector4 with a sl::Vector3 and a scalar (for the forth component). ### function ptr ```cpp inline _FCT_CPU_GPU_ const T * ptr() const ``` Returns a pointer of the first component. ### function setValues ```cpp inline _FCT_CPU_GPU_ Vector4< T > & setValues( const T * vals ) ``` Sets the components of the sl::Vector1 to the values of the argument. ### function operator= ```cpp inline _FCT_CPU_GPU_ Vector4< T > & operator=( const Vector3< T > & other ) ``` Test the equality of the first three components of the sl::Vector4 with a sl::Vector3. ### function operator[] ```cpp inline _FCT_CPU_GPU_ T & operator[]( const unsigned int i ) ``` Returns the **i-th** component. ### function operator[] ```cpp inline _FCT_CPU_GPU_ const T & operator[]( const unsigned int i ) const ``` Returns the **i-th** component. ### function operator[] ```cpp template _FCT_CPU_GPU_ void operator[]( const unsigned int i ) =delete ``` Prevent operator from being called by temporaries (such as rvalue) ### function norm ```cpp inline _FCT_CPU_GPU_ float norm() ``` Returns the norm of the sl::Vector4. ### function square ```cpp inline _FCT_CPU_GPU_ float square() ``` Returns the squared norm of the sl::Vector4. ### function sum ```cpp inline _FCT_CPU_GPU_ float sum() ``` Returns the sum of the components of the sl::Vector4. ### function dot ```cpp static inline _FCT_CPU_GPU_ float dot( const Vector4< T > & a, const Vector4< T > & b ) ``` Returns the dot product of two sl::Vector4. ### function distance ```cpp static inline _FCT_CPU_GPU_ float distance( const Vector4< T > & a, const Vector4< T > & b ) ``` Returns the distance between two sl::Vector4. --- # sl::AI_Model_status **Module:** **Object Detection Module** Structure containing AI model status. `#include ` ## Public Attributes Documentation ### variable downloaded ```cpp bool downloaded; ``` The model file is currently present on the host. ### variable optimized ```cpp bool optimized; ``` An engine file with the expected architecture is found. --- # sl::BatchParameters **Module:** **Object Detection Module** Structure containing a set of parameters for batch object detection. More... `#include ` ## Detailed Description ```cpp class sl::BatchParameters; ``` Structure containing a set of parameters for batch object detection. **Note**: Parameters can be adjusted by the user. The default constructor sets all parameters to their default settings. ## Public Functions Documentation ### function BatchParameters ```cpp BatchParameters( bool enable =false, float id_retention_time =240.f, float batch_duration =2.f ) ``` Default constructor. All the parameters are set to their default values. ## Public Attributes Documentation ### variable enable ```cpp bool enable = false; ``` Whether to enable the batch option in the object detection module. **Note**: To activate this option, enable must be set to true. Batch queueing system provides: * deep-learning based re-identification * trajectory smoothing and filtering ### variable id_retention_time ```cpp float id_retention_time = 240; ``` Max retention time in seconds of a detected object. After this time, the same object will mostly have a different id. ### variable latency ```cpp float latency = 2.f; ``` Trajectories will be output in batch with the desired latency in seconds. **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. * Specifying a long latency will reduce the change of timeout in re-identification but increase difference with live output. During this waiting time, re-identification of objects is done in the background. --- # sl::BodyTrackingFusionParameters **Module:** **Fusion Module** Holds the options used to initialize the body tracking module of the Fusion. `#include ` ## Public Functions Documentation ## Public Attributes Documentation ### variable enable_tracking ```cpp bool enable_tracking = true; ``` Defines if the object detection will track objects across images flow. ### variable enable_body_fitting ```cpp bool enable_body_fitting = false; ``` Defines if the body fitting will be applied. **Note**: If you enable it and the camera provides data as BODY_18 the fused body format will be BODY_34. --- # sl::BodyTrackingFusionRuntimeParameters **Module:** **Fusion Module** Holds the options used to change the behavior of the body tracking module at runtime. `#include ` ## Public Functions Documentation ## Public Attributes Documentation ### variable skeleton_minimum_allowed_keypoints ```cpp int skeleton_minimum_allowed_keypoints = -1; ``` If the fused skeleton has less than skeleton_minimum_allowed_keypoints keypoints, it will be discarded. ### variable skeleton_minimum_allowed_camera ```cpp int skeleton_minimum_allowed_camera = -1; ``` If a skeleton was detected in less than skeleton_minimum_allowed_camera cameras, it will be discarded. ### variable skeleton_smoothing ```cpp float skeleton_smoothing = 0.f; ``` This value controls the smoothing of the tracked or fitted fused skeleton. It is ranged from 0 (low smoothing) and 1 (high smoothing). --- # sl::BodyTrackingRuntimeParameters **Module:** **Body Tracking Module** Structure containing a set of runtime parameters for the body tracking module. More... `#include ` ## Detailed Description ```cpp struct sl::BodyTrackingRuntimeParameters; ``` Structure containing a set of runtime parameters for the body tracking module. **Note**: Parameters can be adjusted by the user. The default constructor sets all parameters to their default settings. ## Public Functions Documentation ### function BodyTrackingRuntimeParameters ```cpp BodyTrackingRuntimeParameters( float detection_confidence_threshold =20.f, int minimum_keypoints_threshold =0, float skeleton_smoothing =0.f ) ``` Default constructor. All the parameters are set to their default values. ## Public Attributes Documentation ### variable detection_confidence_threshold ```cpp float detection_confidence_threshold; ``` Confidence threshold. **Note**: If the scene contains a lot of objects, increasing the confidence can slightly speed up the process, since every object instance is tracked. From 1 to 100, with 1 meaning a low threshold, more uncertain objects and 99 very few but very precise objects. Default: 20.f ### variable minimum_keypoints_threshold ```cpp int minimum_keypoints_threshold; ``` Minimum threshold for the keypoints. **Note**: It is useful, for example, to remove unstable fitting results when a skeleton is partially occluded. The ZED SDK will only output the keypoints of the skeletons with threshold greater than this value. Default: 0 ### variable skeleton_smoothing ```cpp float skeleton_smoothing = 0.f; ``` Control of the smoothing of the fitted fused skeleton. It is ranged from 0 (low smoothing) and 1 (high smoothing). --- # sl::BodyTrackingSensorsParameters `#include ` ## Public Attributes Documentation ### variable instance_module_id ```cpp unsigned int instance_module_id = 0; ``` Id of the module instance. This is used to identify which body tracking module instance is used. ### variable sensors_ids ```cpp std::set< SensorDeviceIdentifier > sensors_ids = {}; ``` 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. ### variable enable_tracking ```cpp bool enable_tracking = true; ``` Whether the body tracking system includes body/person tracking capabilities across a sequence of images. ### variable enable_segmentation ```cpp bool enable_segmentation = false; ``` Whether the body/person masks will be computed. ### variable detection_model ```cpp BODY_TRACKING_MODEL detection_model = BODY_TRACKING_MODEL::HUMAN_BODY_ACCURATE; ``` sl::BODY_TRACKING_MODEL to use. ### variable enable_body_fitting ```cpp bool enable_body_fitting = false; ``` Whether to apply the body fitting. ### variable body_format ```cpp BODY_FORMAT body_format = BODY_FORMAT::BODY_18; ``` Body format to be outputted by the ZED SDK with sl::Camera.retrieveBodies(). ### variable body_selection ```cpp BODY_KEYPOINTS_SELECTION body_selection = BODY_KEYPOINTS_SELECTION::FULL; ``` Selection of keypoints to outputted by the ZED SDK with sl::Camera.retrieveBodies(). ### variable max_range ```cpp float max_range = -1.f; ``` Upper depth range for detections. **Note**: The value cannot be greater than sl::InitParameters.depth_maximum_distance and its unit is defined in sl::InitParameters.coordinate_units. Default: -1.f (value set in sl::InitParameters.depth_maximum_distance) ### variable prediction_timeout_s ```cpp float prediction_timeout_s = 0.2f; ``` Prediction duration of the ZED SDK when an object is not detected anymore before switching its state to sl::OBJECT_TRACKING_STATE::SEARCHING. **Note**: * During this time, the object will have sl::OBJECT_TRACKING_STATE::OK state even if it is not detected. * The duration is expressed in seconds. **Warning**: * prediction_timeout_s will be clamped to 1 second as the prediction is getting worse with time. * Setting this parameter to 0 disables the ZED SDK predictions. It prevents the jittering of the object state when there is a short misdetection. The user can define their own prediction time duration. ### variable allow_reduced_precision_inference ```cpp bool allow_reduced_precision_inference = false; ``` Whether to allow inference to run at a lower precision to improve runtime and memory usage. **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. * 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. * The accuracy loss should not exceed 1-2% on the compatible models. * The current compatible models are all sl::AI_MODELS::HUMAN_BODY_XXXX. It might increase the initial optimization time and could include downloading calibration data or calibration cache and slightly reduce the accuracy. --- # sl::BodyTrackingSensorsRuntimeParameters **Module:** **Body Tracking Module** Structure containing a set of runtime parameters for the body tracking module. More... `#include ` ## Detailed Description ```cpp struct sl::BodyTrackingSensorsRuntimeParameters; ``` Structure containing a set of runtime parameters for the body tracking module. **Note**: Parameters can be adjusted by the user. The default constructor sets all parameters to their default settings. ## Public Attributes Documentation ### variable detection_confidence_threshold ```cpp float detection_confidence_threshold = 20; ``` Confidence threshold. **Note**: If the scene contains a lot of objects, increasing the confidence can slightly speed up the process, since every object instance is tracked. From 1 to 100, with 1 meaning a low threshold, more uncertain objects and 99 very few but very precise objects. Default: 20.f ### variable minimum_keypoints_threshold ```cpp int minimum_keypoints_threshold = 0; ``` Minimum threshold for the keypoints. **Note**: It is useful, for example, to remove unstable fitting results when a skeleton is partially occluded. The ZED SDK will only output the keypoints of the skeletons with threshold greater than this value. Default: 0 ### variable skeleton_smoothing ```cpp float skeleton_smoothing = 0.f; ``` Control of the smoothing of the fitted fused skeleton. It is ranged from 0 (low smoothing) and 1 (high smoothing). ### variable skeleton_minimum_allowed_keypoints ```cpp int skeleton_minimum_allowed_keypoints = -1; ``` If the fused skeleton has less than skeleton_minimum_allowed_keypoints keypoints, it will be discarded. ### variable skeleton_minimum_allowed_camera ```cpp int skeleton_minimum_allowed_camera = -1; ``` If a skeleton was detected in less than skeleton_minimum_allowed_camera cameras, it will be discarded. --- # sl::CameraConfiguration **Module:** **Core Module** Structure containing information about the camera sensor. More... `#include ` ## Detailed Description ```cpp struct sl::CameraConfiguration; ``` Structure containing information about the camera sensor. **Note**: This object is meant to be used as a read-only container, editing any of its field won't impact the ZED SDK. **Warning**: sl::CalibrationParameters are returned in [sl::COORDINATE_SYSTEM::IMAGE], they are not impacted by the sl::InitParameters.coordinate_system. Information about the camera is available in the sl::CameraInformation struct returned by sl::Camera::getCameraInformation(). ## Public Attributes Documentation ### variable calibration_parameters ```cpp CalibrationParameters calibration_parameters; ``` Intrinsics and extrinsic stereo parameters for rectified/undistorted images. ### variable calibration_parameters_raw ```cpp CalibrationParameters calibration_parameters_raw; ``` Intrinsics and extrinsic stereo parameters for unrectified/distorted images. ### variable firmware_version ```cpp unsigned int firmware_version = 0; ``` Internal firmware version of the camera. ### variable fps ```cpp float fps = 0; ``` FPS of the camera. ### variable resolution ```cpp Resolution resolution; ``` Resolution of the camera. --- # sl::CameraInformation **Module:** **Core Module** Structure containing information of a single camera (serial number, model, input type, etc.). More... `#include ` ## Detailed Description ```cpp struct sl::CameraInformation; ``` Structure containing information of a single camera (serial number, model, input type, etc.). **Note**: This object is meant to be used as a read-only container, editing any of its field won't impact the ZED SDK. Information about the camera will be returned by sl::Camera::getCameraInformation(). ## Public Attributes Documentation ### variable serial_number ```cpp unsigned int serial_number = 0; ``` Serial number of the camera. ### variable camera_model ```cpp sl::MODEL camera_model = sl::MODEL::LAST; ``` Model of the camera (see sl::MODEL). ### variable input_type ```cpp sl::INPUT_TYPE input_type = sl::INPUT_TYPE::LAST; ``` Input type used in the ZED SDK. ### variable camera_configuration ```cpp CameraConfiguration camera_configuration; ``` Camera configuration parameters stored in a sl::CameraConfiguration. ### variable sensors_configuration ```cpp SensorsConfiguration sensors_configuration; ``` Sensors configuration parameters stored in a sl::SensorsConfiguration. --- # sl::CameraMetrics **Module:** **Fusion Module** Holds the metrics of a sender in the fusion process. `#include ` ## Public Functions Documentation ### function CameraMetrics ```cpp CameraMetrics() ``` Default constructor. ## Public Attributes Documentation ### variable received_fps ```cpp float received_fps; ``` FPS of the received data. ### variable received_latency ```cpp float received_latency; ``` Latency (in seconds) 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). ### variable synced_latency ```cpp float synced_latency; ``` Latency (in seconds) after Fusion synchronization. Difference between the timestamp of the data received and the timestamp at the end of the Fusion synchronization. ### variable is_present ```cpp bool is_present; ``` Is set to false if no data in this batch of metrics. ### variable ratio_detection ```cpp float ratio_detection; ``` 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. ### variable delta_ts ```cpp float delta_ts; ``` Average data acquisition timestamp difference. Average standard deviation of sender's period since the start. --- # sl::CameraOneConfiguration **Module:** **Core Module** Structure containing information about the camera sensor. More... `#include ` ## Detailed Description ```cpp struct sl::CameraOneConfiguration; ``` Structure containing information about the camera sensor. **Note**: This object is meant to be used as a read-only container, editing any of its field won't impact the ZED SDK. **Warning**: sl::CalibrationParameters are returned in [sl::COORDINATE_SYSTEM::IMAGE], they are not impacted by the sl::InitParametersOne.coordinate_system. Information about the camera is available in the sl::CameraInformation struct returned by sl::CameraOne::getCameraInformation(). ## Public Attributes Documentation ### variable calibration_parameters ```cpp CameraParameters calibration_parameters; ``` Intrinsics and extrinsic stereo parameters for rectified/undistorted images. ### variable calibration_parameters_raw ```cpp CameraParameters calibration_parameters_raw; ``` Intrinsics and extrinsic stereo parameters for unrectified/distorted images. ### variable firmware_version ```cpp unsigned int firmware_version = 0; ``` Internal firmware version of the camera. ### variable fps ```cpp float fps = 0; ``` FPS of the camera. ### variable resolution ```cpp Resolution resolution; ``` Resolution of the camera. --- # sl::CameraOneInformation **Module:** **Core Module** Structure containing information of a single camera (serial number, model, input type, etc.). More... `#include ` ## Detailed Description ```cpp struct sl::CameraOneInformation; ``` Structure containing information of a single camera (serial number, model, input type, etc.). **Note**: This object is meant to be used as a read-only container, editing any of its field won't impact the ZED SDK. Information about the camera will be returned by sl::CameraOne::getCameraInformation(). ## Public Attributes Documentation ### variable serial_number ```cpp unsigned int serial_number = 0; ``` Serial number of the camera. ### variable camera_model ```cpp sl::MODEL camera_model = sl::MODEL::LAST; ``` Model of the camera (see sl::MODEL). ### variable input_type ```cpp sl::INPUT_TYPE input_type = sl::INPUT_TYPE::LAST; ``` Input type used in the ZED SDK. ### variable camera_configuration ```cpp CameraOneConfiguration camera_configuration; ``` Camera configuration parameters stored in a sl::CameraOneConfiguration. ### variable sensors_configuration ```cpp SensorsConfiguration sensors_configuration; ``` Sensors configuration parameters stored in a sl::SensorsConfiguration. --- # sl::CustomObjectDetectionProperties **Module:** **Object Detection Module** Structure containing a set of runtime properties of a certain class ID for the object detection module using a custom model. More... `#include ` ## Detailed Description ```cpp class sl::CustomObjectDetectionProperties; ``` Structure containing a set of runtime properties of a certain class ID for the object detection module using a custom model. **Note**: Parameters can be adjusted by the user. The default constructor sets all parameters to their default settings. ## Public Functions Documentation ### function CustomObjectDetectionProperties ```cpp CustomObjectDetectionProperties( const bool enabled =true, const float detection_confidence_threshold =20.f, const bool is_grounded =true, const bool is_static =false, const float tracking_timeout =-1.f, const float tracking_max_dist =-1.f, const float max_box_width_normalized =-1.f, const float min_box_width_normalized =-1.f, const float max_box_height_normalized =-1.f, const float min_box_height_normalized =-1.f, const float max_box_width_meters =-1.f, const float min_box_width_meters =-1.f, const float max_box_height_meters =-1.f, const float min_box_height_meters =-1.f, const sl::OBJECT_SUBCLASS native_mapped_class =sl::OBJECT_SUBCLASS::LAST, const sl::OBJECT_ACCELERATION_PRESET object_acceleration_preset =sl::OBJECT_ACCELERATION_PRESET::DEFAULT, const float max_allowed_acceleration =std::numeric_limits< float >::quiet_NaN(), const ObjectTrackingParameters & object_tracking_parameters =ObjectTrackingParameters() ) ``` ### function save ```cpp bool save( const String & filename ) const ``` Saves the current set of parameters into a file to be reloaded with the load() method. **Parameters**: * **filename** : Name of the file which will be created to store the parameters (extension '.json' 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. * In case a file already exists, the method will return false and existing file will not be updated. ### function load ```cpp bool load( const String & filename ) ``` Loads a set of parameters from the values contained in a previously saved file. **Parameters**: * **filename** : Path to the file from which the parameters will be loaded (extension '.json' will be added at the end of the filename if not detected). **Return**: True if the file was successfully loaded, otherwise false. ### function encode ```cpp bool encode( String & serialized_content ) const ``` Generate a JSON Object (with the struct type as a key) containing the serialized struct, converted into a string. **Parameters**: * **serialized_content** output string containing the JSON Object **Return**: True if file was successfully saved, otherwise false. ### function decode ```cpp bool decode( const String & serialized_content ) ``` Fill the structure from the serialized json object contained in the input string. **Parameters**: * **serialized_content** input string containing the JSON Object **Return**: True if the decoding was successful, otherwise false. ### function operator== ```cpp bool operator==( const CustomObjectDetectionProperties & props ) const ``` **Parameters**: * **props** CustomObjectDetectionProperties to compare **Return**: true if the two struct are identical Comparison operator == ### function operator!= ```cpp bool operator!=( const CustomObjectDetectionProperties & props ) const ``` **Parameters**: * **props** CustomObjectDetectionProperties to compare **Return**: true if the two struct are different Comparison operator != ## Public Attributes Documentation ### variable enabled ```cpp bool enabled; ``` Whether the object object is kept or not. ### variable detection_confidence_threshold ```cpp float detection_confidence_threshold; ``` Confidence threshold. **Note**: If the scene contains a lot of objects, increasing the confidence can slightly speed up the process, since every object instance is tracked. From 1 to 100, with 1 meaning a low threshold, more uncertain objects and 99 very few but very precise objects. Default: 20.f ### variable is_grounded ```cpp bool is_grounded; ``` Provide hypothesis about the object movements (degrees of freedom or DoF) to improve the object tracking. **Note**: * This parameter cannot be changed for a given object tracking id. * It is advised to set it by labels to avoid issues. * 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). ### variable is_static ```cpp bool is_static; ``` 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. ### variable tracking_timeout ```cpp float tracking_timeout; ``` 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. ### variable tracking_max_dist ```cpp float tracking_max_dist; ``` 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. ### variable max_box_width_normalized ```cpp float max_box_width_normalized; ``` Maximum allowed width normalized to the image size. Any prediction bigger than that will be filtered out. Default: -1 (no filtering) ### variable min_box_width_normalized ```cpp float min_box_width_normalized; ``` Minimum allowed width normalized to the image size. Any prediction smaller than that will be filtered out. Default: -1 (no filtering) ### variable max_box_height_normalized ```cpp float max_box_height_normalized; ``` Maximum allowed height normalized to the image size. Any prediction bigger than that will be filtered out. Default: -1 (no filtering) ### variable min_box_height_normalized ```cpp float min_box_height_normalized; ``` Minimum allowed height normalized to the image size. Any prediction smaller than that will be filtered out. Default: -1 (no filtering) ### variable max_box_width_meters ```cpp float max_box_width_meters; ``` 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) ### variable min_box_width_meters ```cpp float min_box_width_meters; ``` 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) ### variable max_box_height_meters ```cpp float max_box_height_meters; ``` 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) ### variable min_box_height_meters ```cpp float min_box_height_meters; ``` 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) ### variable native_mapped_class ```cpp sl::OBJECT_SUBCLASS native_mapped_class; ``` 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 ### variable object_acceleration_preset ```cpp sl::OBJECT_ACCELERATION_PRESET object_acceleration_preset; ``` Deprecated: Preset defining the expected maximum acceleration of the tracked object. Determines how the ZED SDK interprets object acceleration, affecting tracking behavior and predictions. ### variable max_allowed_acceleration ```cpp float max_allowed_acceleration; ``` Deprecated: 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. ### variable object_tracking_parameters ```cpp ObjectTrackingParameters object_tracking_parameters; ``` Object tracking parameters for this class. --- # sl::CustomObjectDetectionRuntimeParameters **Module:** **Object Detection Module** Structure containing a set of runtime parameters for the object detection module using your own model ran by the SDK. More... `#include ` ## Detailed Description ```cpp class sl::CustomObjectDetectionRuntimeParameters; ``` Structure containing a set of runtime parameters for the object detection module using your own model ran by the SDK. **Note**: Parameters can be adjusted by the user. The default constructor sets all parameters to their default settings. ## Public Functions Documentation ### function CustomObjectDetectionRuntimeParameters ```cpp CustomObjectDetectionRuntimeParameters( const CustomObjectDetectionProperties & object_detection_properties =CustomObjectDetectionProperties {}, const std::unordered_map< int, CustomObjectDetectionProperties > & object_class_detection_properties =std::unordered_map< int, CustomObjectDetectionProperties > {} ) ``` Default constructor. **Parameters**: * **object_detection_properties** Global object properties, when not specified in object_class_detection_properties. * **object_class_detection_properties** Object properties per classes. ## Public Attributes Documentation ### variable object_detection_properties ```cpp CustomObjectDetectionProperties object_detection_properties; ``` Global object detection properties. **Note**: object_detection_properties is used as a fallback when sl::CustomObjectDetectionRuntimeParameters.object_class_detection_properties is partially set. ### variable object_class_detection_properties ```cpp std::unordered_map< int, CustomObjectDetectionProperties > object_class_detection_properties; ``` Per class object detection properties. --- # sl::DeviceProperties **Module:** **Video Module** Structure containing information about the properties of a camera. More... `#include ` ## Detailed Description ```cpp struct sl::DeviceProperties; ``` Structure containing information about the properties of a camera. **Note**: A camera_modelsl::MODEL::ZED_M with an id '-1' can be due to an inverted USB-C cable. ## Public Attributes Documentation ### variable camera_state ```cpp sl::CAMERA_STATE camera_state = sl::CAMERA_STATE::NOT_AVAILABLE; ``` State of the camera. Default: sl::CAMERA_STATE::NOT_AVAILABLE ### variable id ```cpp int id = -1; ``` Id of the camera. Default: -1 ### variable path ```cpp sl::String path; ``` System path of the camera. ### variable video_device ```cpp sl::String video_device; ``` Video device of camera. ### variable i2c_port ```cpp int i2c_port = 0; ``` i2c port of the camera. ### variable camera_model ```cpp sl::MODEL camera_model = sl::MODEL::LAST; ``` Model of the camera. ### variable serial_number ```cpp unsigned int serial_number = 0; ``` Serial number of the camera. **Warning**: Not provided for Windows. Default: 0 ### variable gmsl_port ```cpp int gmsl_port = -1; ``` GMSL port of the camera. ### variable identifier ```cpp unsigned char[3] identifier = {0}; ``` [Cam model, eeprom version, white balance param] ### variable camera_badge ```cpp sl::String camera_badge = ""; ``` Badge name (zedx_ar0234) ### variable camera_sensor_model ```cpp sl::String camera_sensor_model = ""; ``` Name of sensor (zedx) ### variable camera_name ```cpp sl::String camera_name = ""; ``` Name of Camera in DT (ZED_CAM1) ### variable input_type ```cpp INPUT_TYPE input_type = sl::INPUT_TYPE::LAST; ``` Input type of the camera. ### variable sensor_address_left ```cpp unsigned char sensor_address_left = 0; ``` sensor_address when available (ZED-X HDR/XOne HDR only) ### variable sensor_address_right ```cpp unsigned char sensor_address_right = 0; ``` --- # sl::FusionConfiguration **Module:** **Fusion Module** Useful struct to store the Fusion configuration, can be read from /write to a JSON file. `#include ` ## Public Functions Documentation ### function save ```cpp bool save( String filename ) const ``` Saves the current set of parameters into a file to be reloaded with the load() method. **Parameters**: * **filename** : Name of the file which will be created to store the parameters (extension '.json' 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. * In case a file already exists, the method will return false and existing file will not be updated. ### function load ```cpp bool load( String filename ) ``` Loads a set of parameters from the values contained in a previously saved file. **Parameters**: * **filename** : Path to the file from which the parameters will be loaded (extension '.json' will be added at the end of the filename if not detected). **Return**: True if the file was successfully loaded, otherwise false. ### function encode ```cpp bool encode( String & serialized_content ) const ``` Generate a JSON Object (with the struct type as a key) containing the serialized struct, converted into a string. **Parameters**: * **serialized_content** output string containing the JSON Object **Return**: True if file was successfully saved, otherwise false. ### function decode ```cpp bool decode( const String & serialized_content ) ``` Fill the structure from the serialized json object contained in the input string. **Parameters**: * **serialized_content** input string containing the JSON Object **Return**: True if the decoding was successful, otherwise false. ### function operator== ```cpp bool operator==( const FusionConfiguration & param1 ) const ``` Comparison operator ==. **Parameters**: * **param1** to compare **Return**: true if the two struct are identical ### function operator!= ```cpp bool operator!=( const FusionConfiguration & param1 ) const ``` Comparison operator !=. **Parameters**: * **param1** to compare **Return**: true if the two struct are different ## Public Attributes Documentation ### variable serial_number ```cpp int serial_number; ``` The serial number of the used ZED camera. ### variable communication_parameters ```cpp CommunicationParameters communication_parameters; ``` The communication parameters to connect this camera to the Fusion. ### variable pose ```cpp Transform pose; ``` The WORLD Pose of the camera for Fusion in the unit and coordinate system defined by the user in the InitFusionParameters. ### variable input_type ```cpp InputType input_type; ``` The input type for the current camera. ### variable override_gravity ```cpp bool override_gravity = false; ``` 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. --- # sl::FusionMetrics **Module:** **Fusion Module** Holds the metrics of the fusion process. `#include ` ## Public Functions Documentation ### function FusionMetrics ```cpp FusionMetrics() ``` Default constructor. ### function reset ```cpp void reset() ``` Reset the current metrics. ## Public Attributes Documentation ### variable mean_camera_fused ```cpp float mean_camera_fused; ``` Mean number of camera that provides data during the past second. ### variable mean_stdev_between_camera ```cpp float mean_stdev_between_camera; ``` Standard deviation of the data timestamp fused, the lower the better. ### variable camera_individual_stats ```cpp std::map< CameraIdentifier, CameraMetrics > camera_individual_stats; ``` Sender metrics. --- # sl::GNSSCalibrationParameters **Module:** **Fusion Module** Holds the options used for calibrating GNSS / VIO. `#include ` ## Public Functions Documentation ## Public Attributes Documentation ### variable target_yaw_uncertainty ```cpp float target_yaw_uncertainty = 0.1; ``` 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 ### variable enable_translation_uncertainty_target ```cpp bool enable_translation_uncertainty_target = false; ``` 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. ### variable target_translation_uncertainty ```cpp float target_translation_uncertainty = 10e-2; ``` This parameter defines the target translation uncertainty at which the calibration process between GNSS and VIO concludes. Default: 10e-2 (10 centimeters) ### variable enable_reinitialization ```cpp bool enable_reinitialization = true; ``` 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. ### variable gnss_vio_reinit_threshold ```cpp float gnss_vio_reinit_threshold = 5; ``` 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. ### variable enable_rolling_calibration ```cpp bool enable_rolling_calibration = true; ``` 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. ### variable gnss_antenna_position ```cpp sl::float3 gnss_antenna_position; ``` 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. --- # sl::HealthStatus `#include ` ## Public Attributes Documentation ### variable enabled ```cpp bool enabled = false; ``` Indicates if the Health check is enabled. ### variable low_image_quality ```cpp bool low_image_quality = false; ``` 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 sl::Initparameters::enable_image_validity_check to 3 and above ### variable low_lighting ```cpp bool low_lighting = false; ``` 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. ### variable low_depth_reliability ```cpp bool low_depth_reliability = false; ``` 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. ### variable low_motion_sensors_reliability ```cpp bool low_motion_sensors_reliability = false; ``` 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. --- # sl::InitFusionParameters **Module:** **Fusion Module** Holds the options used to initialize the Fusion object. `#include ` ## Public Functions Documentation ### function InitFusionParameters ```cpp InitFusionParameters( UNIT coordinate_units_ =UNIT::MILLIMETER, COORDINATE_SYSTEM coordinate_system_ =COORDINATE_SYSTEM::IMAGE, bool output_performance_metrics =true, int verbose_ =0, unsigned timeout_period_number_ =5, int sdk_gpu_id_ =-1, CUcontext sdk_cuda_ctx_ =CUcontext(), SynchronizationParameter synchronization_parameters_ =SynchronizationParameter(), sl::Resolution maximum_working_resolution_ =sl::Resolution(-1, -1) ) ``` Default constructor. ## Public Attributes Documentation ### variable coordinate_units ```cpp UNIT coordinate_units; ``` 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::MILLIMETER ### variable coordinate_system ```cpp COORDINATE_SYSTEM coordinate_system; ``` 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::IMAGE ### variable output_performance_metrics ```cpp bool output_performance_metrics; ``` It allows users to extract some stats of the Fusion API like drop frame of each camera, latency, etc... ### variable verbose ```cpp int verbose; ``` Enable the verbosity mode of the SDK. ### variable timeout_period_number ```cpp unsigned timeout_period_number; ``` 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. **Note**: This parameter is deprecated. Use `data_source_timeout` present in `synchronization_parameters` instead. ### variable sdk_gpu_id ```cpp CUdevice sdk_gpu_id; ``` NVIDIA graphics card to use. **Note**: A non-positive value will search for all CUDA capable devices and select the most powerful. 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 ### variable sdk_cuda_ctx ```cpp CUcontext sdk_cuda_ctx; ``` CUcontext to be used. **Note**: * When creating you own CUDA context, you have to define the device you will use. Do not forget to also specify it on sdk_gpu_id. * **On Jetson**, you have to set the flag CU_CTX_SCHED_YIELD, during CUDA context creation. * You can also let the SDK create its own context, and use sl::Camera::getCUDAContext() to use it. If your application uses another CUDA-capable library, giving its CUDA context to the ZED SDK can be useful when sharing GPU memories. This parameter allows you to set the CUDA context to be used by the ZED SDK. Leaving this parameter empty asks the SDK to create its own context. Default: (empty) ### variable synchronization_parameters ```cpp SynchronizationParameter synchronization_parameters; ``` Specifies the parameters used for data synchronization during fusion. The SynchronizationParameter struct encapsulates the synchronization parameters that control the data fusion process. ### variable maximum_working_resolution ```cpp sl::Resolution maximum_working_resolution; ``` 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. --- # sl::InitLidarParameters **Module:** **Lidar Module** Structure containing the options used to initialize the Lidar object. `#include ` ## Public Functions Documentation ### function InitLidarParameters ```cpp inline InitLidarParameters() ``` ## Public Attributes Documentation ### variable input ```cpp sl::InputType input; ``` Input type (stream, etc.). ### variable mode ```cpp LIDAR_MODE mode = LIDAR_MODE::AUTO; ``` Lidar mode (resolution and frequency). Default: sl::LIDAR_MODE::AUTO. ### variable depth_minimum_distance ```cpp float depth_minimum_distance = 0.0f; ``` Minimum distance for data. Default: 0.0f (no limit) ### variable depth_maximum_distance ```cpp float depth_maximum_distance = 0.0f; ``` Maximum distance for data. Default: 0.0f (no limit) ### variable coordinate_units ```cpp sl::UNIT coordinate_units = sl::UNIT::METER; ``` Unit of spatial data. Default: sl::UNIT::METER. ### variable coordinate_system ```cpp sl::COORDINATE_SYSTEM coordinate_system = sl::COORDINATE_SYSTEM::IMAGE; ``` Coordinate system for spatial data. Default: sl::COORDINATE_SYSTEM::IMAGE. ### variable svo_real_time_mode ```cpp bool svo_real_time_mode = false; ``` Defines if the Lidar object returns frames in real-time mode. **Note**: Lidar::grab() will return an error when trying to play too fast, and frames will be dropped when playing too slowly. When playing back an OSF file, each call to Lidar::grab() will extract a new frame and use it. However, it ignores the real capture rate of the data saved in the OSF file. Enabling this parameter will bring the SDK closer to a real simulation when playing back a file by using the frames' timestamps. Default: false ### variable auto_recovery_on_config_change ```cpp bool auto_recovery_on_config_change = true; ``` Enables automatic recovery when the sensor's configuration changes externally. When another client changes the sensor's configuration (resolution, FPS, multicast settings, etc.) while this client is streaming, the SDK can automatically detect this and reconnect. If enabled (default), grab() will return [ERROR_CODE::SENSOR_CONFIGURATION_CHANGED] once after successful recovery, then resume normal operation. If disabled, grab() will return [ERROR_CODE::SENSOR_CONFIGURATION_CHANGED] and enter failure mode. Subsequent calls to grab() will fail until the Lidar is closed and reopened. Default: true ### variable multicast_mode ```cpp LIDAR_MULTICAST_MODE multicast_mode = LIDAR_MULTICAST_MODE::AUTO; ``` Multicast streaming mode. Controls whether the sensor uses multicast (multiple clients can receive) or unicast (single client). See LIDAR_MULTICAST_MODE for detailed behavior of each mode. Default: sl::LIDAR_MULTICAST_MODE::AUTO ### variable multicast_group ```cpp std::string multicast_group; ``` Multicast group IP address. Optional multicast IP address in the range 239.0.0.0 - 239.255.255.255 (administratively scoped). - If empty and multicast_mode is ON: SDK auto-selects 239.201.201.201 - If set and valid: used when enabling multicast - If set and invalid: behavior depends on multicast_mode - AUTO: returns [ERROR_CODE::CONFIGURATION_FALLBACK], falls back to current sensor config - ON: returns [ERROR_CODE::INVALID_FUNCTION_PARAMETERS] (hard fail) Default: "" (empty) ### variable sdk_gpu_id ```cpp CUdevice sdk_gpu_id; ``` NVIDIA graphics card to use. By default the Lidar class will not use the GPU currently, this can be enabled with the env variable ZED_SDK_LIDAR_CUDA_PROCESSING. . **Note**: A non-positive value will search for all CUDA capable devices and select the most powerful. 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 ### variable sdk_cuda_ctx ```cpp CUcontext sdk_cuda_ctx; ``` CUcontext to be used. **Note**: * When creating you own CUDA context, you have to define the device you will use. Do not forget to also specify it on sdk_gpu_id. * **On Jetson**, you have to set the flag CU_CTX_SCHED_YIELD, during CUDA context creation. * You can also let the SDK create its own context, and use sl::Camera::getCUDAContext() to use it. * If you create your own CUDA context, you must ensure that it is destroyed after all SDK objects (sl::Camera, sl::Fusion) are destroyed. If your application uses another CUDA-capable library, giving its CUDA context to the ZED SDK can be useful when sharing GPU memories. This parameter allows you to set the CUDA context to be used by the ZED SDK. Leaving this parameter empty asks the SDK to create its own context. Default: (empty) ### variable sdk_verbose ```cpp int sdk_verbose = 1; ``` Set the verbosity level of the SDK. **Note**: The verbose messages can also be exported into a log file. See sdk_verbose_log_file for more. 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 (enabled) ### variable sdk_verbose_log_file ```cpp String sdk_verbose_log_file; ``` File path to store the Lidar SDK logs (if sdk_verbose is enabled). The file will be created if it does not exist. Default: "" (empty, logs are printed to console only) --- # sl::InitParametersOne **Module:** **Video Module** Class containing the options used to initialize the sl::CameraOne object. More... `#include ` ## Detailed Description ```cpp class sl::InitParametersOne; ``` Class containing the options used to initialize the sl::CameraOne object. This class allows you to select parameters for the sl::CameraOne such as its input, live or playback, its resolution, its frame rate... Once filled with the desired options, it should be passed to the sl::CameraOne.open() method. You can customize it to fit your application. ## Public Functions Documentation ## Public Attributes Documentation ### variable camera_resolution ```cpp sl::RESOLUTION camera_resolution = sl::RESOLUTION::AUTO; ``` Desired camera resolution. **Note**: Available resolutions are listed here: sl::RESOLUTION. Default: AUTO ### variable camera_fps ```cpp int camera_fps = 0; ``` Requested camera frame rate. **Note**: If the requested camera_fps is unsupported, the closest available FPS will be used. 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. ### variable camera_image_flip ```cpp int camera_image_flip = 0; ``` 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::OFF ### variable svo_real_time_mode ```cpp bool svo_real_time_mode = false; ``` Defines if SVO playback will return frame to fit the real time. **Note**: sl::CameraOne::grab() will return an error when trying to play too fast, and frames will be dropped when playing too slowly. When playing back an SVO file, each call to sl::CameraOne::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 ### variable coordinate_units ```cpp sl::UNIT coordinate_units = sl::UNIT::MILLIMETER; ``` Unit of spatial data . Default: sl::UNIT::MILLIMETER. ### variable coordinate_system ```cpp sl::COORDINATE_SYSTEM coordinate_system = sl::COORDINATE_SYSTEM::IMAGE; ``` 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::CameraOne object to return its measures. This defines the order and the direction of the axis of the coordinate system. Default: sl::COORDINATE_SYSTEM::IMAGE ### variable sdk_cuda_ctx ```cpp CUcontext sdk_cuda_ctx = nullptr; ``` CUcontext to be used. **Note**: * When creating you own CUDA context, you have to define the device you will use. * **On Jetson**, you have to set the flag CU_CTX_SCHED_YIELD, during CUDA context creation. If your application uses another CUDA-capable library, giving its CUDA context to the ZED SDK can be useful when sharing GPU memories. This parameter allows you to set the CUDA context to be used by the ZED SDK. Leaving this parameter empty asks the SDK to create its own context. Default: (empty) ### variable sdk_gpu_id ```cpp CUdevice sdk_gpu_id = -1; ``` NVIDIA graphics card to use. **Note**: A non-positive value will search for all CUDA capable devices and select the most powerful. 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 ### variable sdk_verbose ```cpp int sdk_verbose = 1; ``` Enable the ZED SDK verbose mode. **Note**: * The verbose messages can also be exported into a log file. * See sdk_verbose_log_file for more. 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 message enabled) ### variable sdk_verbose_log_file ```cpp String sdk_verbose_log_file; ``` File path to store the ZED SDK logs (if sdk_verbose is enabled). **Note**: * Setting this parameter to any value will redirect all standard output print calls of the entire program. * This means that your own standard output print calls will be redirected to the log file. * This parameter can be particularly useful for creating a log system, and with Unreal or Unity applications that don't provide a standard console output. **Warning**: * The log file won't be cleared after successive executions of the application. * This means that it can grow indefinitely if not cleared. The file will be created if it does not exist. Default: "" ### variable input ```cpp InputType input; ``` Defines the input source to initialize and open an sl::CameraOne object from. **Note**: * Available cameras and their id/serial number can be listed using sl::CameraOne::getDeviceList() and sl::CameraOne::getStreamingDeviceList(). * Each sl::CameraOne will create its own memory (CPU and GPU), therefore the number of cameras used at the same time can be limited by the configuration of your computer (GPU/CPU memory and capabilities). * See sl::InputType for complementary information. The SDK can handle different input types: * Select a camera by its ID (only take care of ZED X-One camera) ```cpp InitParametersOne init_params; // Set initial parameters init_params.input.setFromCameraID(0); // Selects the camera with ID = 0 ``` * Select a camera by its serial number ```cpp InitParametersOne init_params; // Set initial parameters init_params.input.setFromSerialNumber(1010); // Selects the camera with serial number = 1010 ``` * Open a recorded sequence in the SVO file format ```cpp InitParametersOne init_params; // Set initial parameters init_params.input.setFromSVOFile("/path/to/file.svo"); // Selects the and SVO file to be read ``` * Open a streaming camera from its IP address and port ```cpp InitParametersOne init_params; // Set initial parameters init_params.input.setFromStream("192.168.1.42"); // Selects the IP address of the streaming camera. A second optional parameter is available for port selection. ``` Default : (empty) ### variable optional_settings_path ```cpp String optional_settings_path; ``` Optional path where the ZED SDK has to search for the settings file (_SN.conf_ file). **Note**: * The settings file will be searched in the default directory: * **Linux**: _/usr/local/zed/settings/_ * **Windows**: _C:/ProgramData/stereolabs/settings_ * If a path is specified and no file has been found, the ZED SDK will search the settings file in the default directory. * An automatic download of the settings file (through **ZED Explorer** or the installer) will still download the files on the default path. This file contains the calibration information of the camera. Default: "" ```cpp InitParametersOne init_params; // Set initial parameters std::string home = getenv("HOME"); // Get /home/user as string using getenv() std::string path = home + "/Documents/settings/"; // Assuming /home//Documents/settings/SNXXXX.conf exists. Otherwise, it will be searched in /usr/local/zed/settings/ init_params.optional_settings_path = sl::String(path.c_str()); ``` ### variable optional_opencv_calibration_file ```cpp String optional_opencv_calibration_file; ``` 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. * The file must be in a XML/YAML/JSON formatting provided by OpenCV. * It also must contain the following keys: Size, K (intrinsic), D (distortion). **Warning**: Erroneous calibration values can lead to poor accuracy in all ZED SDK modules. ### variable async_grab_camera_recovery ```cpp bool async_grab_camera_recovery = false; ``` Define the behavior of the automatic camera recovery during sl::CameraOne::grab() method call. When async is enabled and there's an issue with the communication with the sl::CameraOne object, sl::CameraOne::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::CameraOne::grab() method is blocking and will return only once the camera communication is restored or the timeout is reached. Default: false ### variable enable_hdr ```cpp bool enable_hdr = false; ``` Define the HDR mode when available. When set to true, the camera will be set in HDR mode if the camera model and resolution allows it. Otherwise, the camera will be fallback to a compatible mode. HDR (High Dynamic Range) enhances image quality in scenes with high contrast, providing greater detail in both the brightest and darkest areas. Default: false ### variable svo_decryption_key ```cpp String svo_decryption_key; ``` Optional passphrase or key to decrypt an encrypted SVO file. **Note**: If the SVO file is encrypted and this field is empty or contains a wrong key, sl::CameraOne::open() will return [ERROR_CODE::INVALID_SVO_FILE]. Required when opening an SVO file that was recorded with RecordingParameters::encryption_key. The value follows the same interpretation rules (file path, hex key, or passphrase). Default: "" (no decryption) --- # sl::InitSensorsParameters `#include ` ## Public Attributes Documentation ### variable coordinate_units ```cpp UNIT coordinate_units = sl::UNIT::MILLIMETER; ``` 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::MILLIMETER ### variable coordinate_system ```cpp COORDINATE_SYSTEM coordinate_system = sl::COORDINATE_SYSTEM::IMAGE; ``` 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::IMAGE ### variable output_performance_metrics ```cpp bool output_performance_metrics = false; ``` It allows users to extract some stats of the Fusion API like drop frame of each camera, latency, etc... ### variable verbose ```cpp int verbose = 0; ``` Enable the verbosity mode of the SDK. ### variable sdk_gpu_id ```cpp CUdevice sdk_gpu_id = -1; ``` NVIDIA graphics card to use. **Note**: A non-positive value will search for all CUDA capable devices and select the most powerful. 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 ### variable sdk_cuda_ctx ```cpp CUcontext sdk_cuda_ctx = CUcontext(); ``` CUcontext to be used. **Note**: * When creating you own CUDA context, you have to define the device you will use. Do not forget to also specify it on sdk_gpu_id. * **On Jetson**, you have to set the flag CU_CTX_SCHED_YIELD, during CUDA context creation. * You can also let the SDK create its own context, and use sl::Camera::getCUDAContext() to use it. If your application uses another CUDA-capable library, giving its CUDA context to the ZED SDK can be useful when sharing GPU memories. This parameter allows you to set the CUDA context to be used by the ZED SDK. Leaving this parameter empty asks the SDK to create its own context. Default: (empty) ### variable maximum_working_resolution ```cpp sl::Resolution maximum_working_resolution = sl::Resolution(0, 0); ``` Set a maximum size for all SDK output, like retrieveImage and retrieveMeasure functions. **Note**: If maximum_working_resolution dimensions are lower than 64, it will be interpreted as a dividing scale factor; * maximum_working_resolution = sl::Resolution(1280, 2) -> 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 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 versions where (0,0) meant the native image size. ### variable execution_mode ```cpp SENSORS_EXECUTION_MODE execution_mode = SENSORS_EXECUTION_MODE::EAGER; ``` Execution mode for the Sensors pipeline. **Note**: Can be overridden by env var ZED_SDK_SENSORS_EXECUTION_MODE ("pipelined"/"eager"). **Warning**: * Enabling PIPELINED mode changes the threading model — each device gets its own worker thread. * Mat returned from retrieve*() in PIPELINED mode are shallow copies (read-only). Do not modify them. Controls whether `process()` runs synchronously (EAGER) or spawns a pipelined producer/consumer architecture with dedicated worker threads (PIPELINED). In PIPELINED mode: * All modules (Object Detection, Body Tracking, Positional Tracking) must be enabled BEFORE first process() * The first process() + retrieve*() cycle is the **setup phase**: it runs synchronously while learning which outputs the user needs (device + view/measure + resolution + memory type) * On the next process() call, dedicated worker threads are spawned (one per device). Each worker continuously calls grab() at the device's native frame rate and writes into triple-buffered outputs (lock-free mailbox) * Subsequent process() calls return immediately (non-blocking); they only check worker health * retrieve*() reads from the latest completed buffer * Use sync_policy to control temporal alignment across devices Default: SENSORS_EXECUTION_MODE::EAGER ### variable sync_policy ```cpp SENSORS_SYNC_POLICY sync_policy = SENSORS_SYNC_POLICY::NONE; ``` Synchronization policy for pipelined mode retrieval. **Note**: Only effective when execution_mode is PIPELINED; EAGER mode has no per-device buffers/queues, so the SDK cannot apply cross-device temporal alignment or stale-frame rejection. Controls how data from devices running at different frequencies is synchronized: * NONE: Each retrieve returns the device's latest data (no temporal alignment) * CLOSEST: Align all devices to a common sync timestamp (oldest "latest") * DROP_STALE: Same as CLOSEST, but returns error if any device data exceeds sync_tolerance Default: SENSORS_SYNC_POLICY::NONE ### variable sync_tolerance ```cpp sl::Timestamp sync_tolerance = sl::Timestamp::fromMilliseconds(50); ``` Maximum timestamp difference for synchronized retrieval in pipelined mode. **Note**: Only effective when execution_mode is PIPELINED and sync_policy != NONE (EAGER mode does not maintain the buffered history needed for sync alignment). When sync_policy is CLOSEST or DROP_STALE, frames with timestamp difference greater than this value from the sync timestamp are considered stale. * With CLOSEST: Stale data is still returned (best-effort) * With DROP_STALE: Returns [SENSORS_ERROR_CODE::STALE_DATA] if stale Default: 50ms --- # sl::LidarCalibration **Module:** **Lidar Module** Structure containing beam geometry calibration data for raw data processing. More... `#include ` ## Detailed Description ```cpp struct sl::LidarCalibration; ``` Structure containing beam geometry calibration data for raw data processing. **Note**: This structure is meant to be used as a read-only container. This calibration data is required for: * Destaggering raw sensor data (using pixel_shift_by_row) * Custom XYZ projection from range data (using beam angles) * Advanced point cloud processing pipelines ## Public Attributes Documentation ### variable beam_altitude_angles ```cpp std::vector< double > beam_altitude_angles; ``` Vertical angle of each beam in degrees. **Note**: * Size equals vertical_resolution (number of channels). * Used with beam_azimuth_angles to compute XYZ from range. ### variable beam_azimuth_angles ```cpp std::vector< double > beam_azimuth_angles; ``` Horizontal angle offset of each beam in degrees. **Note**: * Size equals vertical_resolution (number of channels). * Accounts for beam stagger pattern in the azimuth direction. ### variable pixel_shift_by_row ```cpp std::vector< int > pixel_shift_by_row; ``` Per-row pixel shift for destaggering raw data. **Note**: * Size equals vertical_resolution (number of channels). * Apply this shift to align columns in staggered raw data. ### variable lidar_origin_to_beam_origin_mm ```cpp double lidar_origin_to_beam_origin_mm = 0.0; ``` Distance from lidar origin to beam origin in millimeters. **Note**: Used for accurate near-field range correction. ### variable beam_to_lidar_transform ```cpp sl::Matrix4f beam_to_lidar_transform; ``` 4x4 transform from beam frame to lidar frame. **Note**: Row-major order. --- # sl::LidarDeviceProperties **Module:** **Lidar Module** Structure containing properties of a discovered Lidar device. More... `#include ` ## Detailed Description ```cpp struct sl::LidarDeviceProperties; ``` Structure containing properties of a discovered Lidar device. This structure is populated during device discovery (getDeviceList()). For full sensor configuration and calibration data, use getLidarInformation() after opening. ## Public Attributes Documentation ### variable name ```cpp sl::String name; ``` Device name, e.g. "OS1-128". ### variable ip_address ```cpp sl::String ip_address; ``` IP address of the device. ### variable port ```cpp int port = 0; ``` UDP port for lidar data. ### variable imu_port ```cpp int imu_port = 0; ``` UDP port for IMU data. ### variable sensor_state ```cpp sl::SENSOR_STATE sensor_state = sl::SENSOR_STATE::AVAILABLE; ``` Availability state. ### variable lidar_information ```cpp LidarInformation lidar_information; ``` Device information (serial number, firmware, configuration, etc.). **Note**: During discovery, calibration data may not be fully populated. --- # sl::LidarInformation **Module:** **Lidar Module** Structure containing information about the Lidar device. More... `#include ` ## Detailed Description ```cpp struct sl::LidarInformation; ``` Structure containing information about the Lidar device. **Note**: This structure is meant to be used as a read-only container. Information about the lidar will be returned by sl::Lidar::getLidarInformation(). ## Public Attributes Documentation ### variable serial_number ```cpp sl::String serial_number; ``` Serial number of the device. ### variable firmware_version ```cpp sl::String firmware_version; ``` Firmware version. ### variable product_line ```cpp sl::String product_line; ``` Product line (e.g., "OS1", "OS2"). ### variable product_part_number ```cpp sl::String product_part_number; ``` Product part number. ### variable build_date ```cpp sl::String build_date; ``` Build date of the firmware. ### variable image_rev ```cpp sl::String image_rev; ``` Image revision. ### variable status ```cpp sl::String status; ``` Current sensor status. ### variable sensor_configuration ```cpp LidarSensorConfiguration sensor_configuration; ``` Sensor configuration (resolution, fps, calibration, etc.). --- # sl::LidarSensorConfiguration **Module:** **Lidar Module** Structure containing runtime configuration of the Lidar sensor. More... `#include ` ## Detailed Description ```cpp struct sl::LidarSensorConfiguration; ``` Structure containing runtime configuration of the Lidar sensor. **Note**: This structure is meant to be used as a read-only container. This includes resolution, frame rate, field of view, and calibration data. Available after the Lidar is opened via LidarInformation. ## Public Attributes Documentation ### variable vertical_resolution ```cpp int vertical_resolution = 0; ``` Vertical resolution (number of channels/beams). **Note**: Depends on the hardware model (e.g., 32, 64, 128). ### variable horizontal_resolution ```cpp int horizontal_resolution = 0; ``` Horizontal resolution (number of columns per frame). **Note**: Depends on the configured mode (e.g., 512, 1024, 2048). ### variable fps ```cpp float fps = 0.0f; ``` Frame rate in Hz. **Note**: Depends on the configured mode (e.g., 10, 20). ### variable vertical_fov ```cpp float vertical_fov = 0.0f; ``` Vertical field of view in degrees. **Note**: Computed from beam_altitude_angles range. ### variable horizontal_fov ```cpp float horizontal_fov = 360.0f; ``` Horizontal field of view in degrees. **Note**: Typically 360 for spinning lidars. ### variable calibration ```cpp LidarCalibration calibration; ``` Beam geometry calibration for raw data processing. ### variable imu_to_lidar_transform ```cpp sl::Transform imu_to_lidar_transform; ``` Transform from IMU frame to Lidar frame. **Note**: Used for sensor fusion and motion compensation. --- # sl::ObjectDetectionFusionParameters **Module:** **Fusion Module** Holds the options used to initialize the object detection module of the Fusion. `#include ` ## Public Functions Documentation ## Public Attributes Documentation ### variable enable_tracking ```cpp bool enable_tracking = true; ``` Defines if the object detection will track objects across images flow. --- # sl::ObjectDetectionRuntimeParameters **Module:** **Object Detection Module** Structure containing a set of runtime parameters for the object detection module. More... `#include ` ## Detailed Description ```cpp class sl::ObjectDetectionRuntimeParameters; ``` Structure containing a set of runtime parameters for the object detection module. **Note**: Parameters can be adjusted by the user. The default constructor sets all parameters to their default settings. ## Public Functions Documentation ### function ObjectDetectionRuntimeParameters ```cpp ObjectDetectionRuntimeParameters( const float detection_confidence_threshold =20.f, const std::vector< OBJECT_CLASS > & object_class_filter =std::vector< OBJECT_CLASS > {}, const std::map< OBJECT_CLASS, float > & object_class_detection_confidence_threshold =std::map< OBJECT_CLASS, float > {}, const ObjectTrackingParameters & object_tracking_parameters =ObjectTrackingParameters(), const std::map< OBJECT_CLASS, ObjectTrackingParameters > & object_class_tracking_parameters =std::map< OBJECT_CLASS, ObjectTrackingParameters > {} ) ``` Default constructor. **Parameters**: * **detection_confidence_threshold** Confidence threshold. * **object_class_filter** Object class filter. * **object_class_detection_confidence_threshold** Map of confidence threshold per classes. * **object_tracking_parameters** Global tracking parameters. * **object_class_tracking_parameters** Map of tracking parameters per classes. ## Public Attributes Documentation ### variable detection_confidence_threshold ```cpp float detection_confidence_threshold; ``` Confidence threshold. **Note**: * If the scene contains a lot of objects, increasing the confidence can slightly speed up the process, since every object instance is tracked. * detection_confidence_threshold is used as a fallback when sl::ObjectDetectionRuntimeParameters.object_class_detection_confidence_threshold is partially set. From 1 to 100, with 1 meaning a low threshold, more uncertain objects and 99 very few but very precise objects. Default: 20.f ### variable object_class_filter ```cpp std::vector< OBJECT_CLASS > object_class_filter; ``` Defines which object types to detect and track. **Note**: * Fewer object types can slightly speed up the process since every object is tracked. * Will output only the selected classes. Default: {} (all classes are tracked) In order to get all the available classes, the filter vector must be empty : ```cpp object_class_filter = {}; ``` To select a set of specific object classes, like vehicles, persons and animals for instance: ```cpp object_class_filter = {OBJECT_CLASS::VEHICLE, OBJECT_CLASS::PERSON, OBJECT_CLASS::ANIMAL}; ``` ### variable object_class_detection_confidence_threshold ```cpp std::map< OBJECT_CLASS, float > object_class_detection_confidence_threshold; ``` Map 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. ### variable object_tracking_parameters ```cpp ObjectTrackingParameters object_tracking_parameters; ``` Global tracking parameters. ### variable object_class_tracking_parameters ```cpp std::map< OBJECT_CLASS, ObjectTrackingParameters > object_class_tracking_parameters; ``` Map of tracking parameters for each class (can be empty for some classes). **Note**: sl::ObjectDetectionRuntimeParameters.object_tracking_parameters will be taken as fallback/default value. --- # sl::ObjectDetectionSensorsParameters `#include ` ## Public Attributes Documentation ### variable instance_module_id ```cpp unsigned int instance_module_id = 0; ``` Id of the module instance. This is used to identify which object detection module instance is used. ### variable sensors_ids ```cpp std::set< SensorDeviceIdentifier > sensors_ids = {}; ``` List of sensor id that will be used for this instance By default empty which means all available sensors in Sensors when the object detection instance is started. ### variable fused_objects_group_name ```cpp sl::String fused_objects_group_name; ``` 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. ### variable enable_tracking ```cpp bool enable_tracking = true; ``` Whether the object detection system includes object tracking capabilities across a sequence of images. ### variable enable_segmentation ```cpp bool enable_segmentation = false; ``` Whether the object masks will be computed. ### variable detection_model ```cpp OBJECT_DETECTION_MODEL detection_model = OBJECT_DETECTION_MODEL::MULTI_CLASS_BOX_FAST; ``` sl::OBJECT_DETECTION_MODEL to use. ### variable custom_onnx_file ```cpp sl::String custom_onnx_file; ``` Path to the YOLO-like onnx file for custom object detection ran in the ZED SDK. **Note**: This parameter is useless when detection_model is not [OBJECT_DETECTION_MODEL::CUSTOM_YOLOLIKE_BOX_OBJECTS]. **Attention**: * - The model must be a YOLO-like model. * - The caching uses the deserialized `custom_onnx_file` along with your GPU specs to decide whether to use the cached optmized model or to optimize the passed onnx model. If you change the weights of the onnx file and pass the same path, the ZED SDK will detect the difference and optimize the new model. 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. ### variable custom_onnx_dynamic_input_shape ```cpp sl::Resolution custom_onnx_dynamic_input_shape = sl::Resolution(512, 512); ``` 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) ### variable max_range ```cpp float max_range = -1.f; ``` Upper depth range for detections. **Note**: The value cannot be greater than sl::InitParameters.depth_maximum_distance and its unit is defined in sl::InitParameters.coordinate_units. Default: -1.f (value set in sl::InitParameters.depth_maximum_distance) ### variable filtering_mode ```cpp OBJECT_FILTERING_MODE filtering_mode = OBJECT_FILTERING_MODE::NMS3D; ``` Filtering mode that should be applied to raw detections. **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. * For custom object, it is recommended to use sl::OBJECT_FILTERING_MODE::NMS_3D_PER_CLASS or sl::OBJECT_FILTERING_MODE::NONE. * In this case, you might need to add your own NMS filter before ingesting the boxes into the object detection module. Default: sl::OBJECT_FILTERING_MODE::NMS_3D (same behavior as previous ZED SDK version) ### variable prediction_timeout_s ```cpp float prediction_timeout_s = 0.2f; ``` Prediction duration of the ZED SDK when an object is not detected anymore before switching its state to sl::OBJECT_TRACKING_STATE::SEARCHING. **Note**: * During this time, the object will have sl::OBJECT_TRACKING_STATE::OK state even if it is not detected. * The duration is expressed in seconds. **Warning**: * prediction_timeout_s will be clamped to 1 second as the prediction is getting worse with time. * Setting this parameter to 0 disables the ZED SDK predictions. It prevents the jittering of the object state when there is a short misdetection. The user can define their own prediction time duration. --- # sl::ObjectTrackingParameters **Module:** **Object Detection Module** Structure containing a set of parameters for the object tracking module. More... `#include ` ## Detailed Description ```cpp class sl::ObjectTrackingParameters; ``` Structure containing a set of parameters for the object tracking module. **Note**: Parameters can be adjusted by the user. The default constructor sets all parameters to their default settings. ## Public Functions Documentation ### function ObjectTrackingParameters ```cpp ObjectTrackingParameters( sl::OBJECT_ACCELERATION_PRESET object_acceleration_preset =sl::OBJECT_ACCELERATION_PRESET::DEFAULT, float velocity_smoothing_factor =-1.f, float min_velocity_threshold =-1.f, float prediction_timeout_s =-1.f, float min_confirmation_time_s =-1.f ) ``` Default constructor. ## Public Attributes Documentation ### variable object_acceleration_preset ```cpp sl::OBJECT_ACCELERATION_PRESET object_acceleration_preset; ``` Preset defining the expected maximum acceleration of the tracked object. Determines how the ZED SDK interprets object acceleration, affecting tracking behavior and predictions. ### variable velocity_smoothing_factor ```cpp float velocity_smoothing_factor; ``` Control the smoothing of the velocity estimation. Manually override the acceleration preset. 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 ### variable min_velocity_threshold ```cpp float min_velocity_threshold; ``` 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 minimum velocity threshold. Default: -1. ### variable prediction_timeout_s ```cpp float prediction_timeout_s; ``` 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. Default: -1 ### variable min_confirmation_time_s ```cpp float min_confirmation_time_s; ``` 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 minimum confirmation time. Default: -1. --- # sl::PlaneDetectionParameters **Module:** **Spatial Mapping Module** Structure containing a set of parameters for the plane detection functionality. More... `#include ` ## Detailed Description ```cpp class sl::PlaneDetectionParameters; ``` Structure containing a set of parameters for the plane detection functionality. **Note**: Parameters can be adjusted by the user. The default constructor sets all parameters to their default settings. ## Public Functions Documentation ## Public Attributes Documentation ### variable max_distance_threshold ```cpp float max_distance_threshold = 0.15f; ``` Controls the spread of plane by checking the position difference. Default: 0.15 meters ### variable normal_similarity_threshold ```cpp float normal_similarity_threshold = 15.f; ``` Controls the spread of plane by checking the angle difference. Default: 15 degrees --- # sl::PositionalTrackingFusionParameters **Module:** **Fusion Module** Holds the options used for initializing the positional tracking fusion module. `#include ` ## Public Functions Documentation ## Public Attributes Documentation ### variable enable_GNSS_fusion ```cpp bool enable_GNSS_fusion = false; ``` This attribute is responsible for enabling or not GNSS positional tracking fusion. ### variable gnss_calibration_parameters ```cpp GNSSCalibrationParameters gnss_calibration_parameters; ``` Control the VIO / GNSS calibration process. ### variable base_footprint_to_world_transform ```cpp Transform base_footprint_to_world_transform; ``` 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. **Note**: base footprint is the coordinate frame attached to the projected baselink coordinate frame on the ground. It is generally a constant offset between baselink and the ground. Fusion uses the base footprint coordinate frame to determine where is the ground with respect to the tracked baselink position and orientation. baselink is the root coordinate frame of the robot. Fusion configuration file must give the position and orientation of each camera with respect to the baselink ### variable base_footprint_to_baselink_transform ```cpp Transform base_footprint_to_baselink_transform; ``` 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. **Note**: This transform is used by the Fusion to determine where is the ground with respect to the baselink coordinate frame which is the root coordinate frame of Fusion. ### variable set_gravity_as_origin ```cpp bool set_gravity_as_origin = false; ``` Whether to override 2 of the 3 rotations from base_footprint_to_world_transform using the IMU gravity. ### variable tracking_camera_id ```cpp CameraIdentifier tracking_camera_id; ``` ID of the camera used for positional tracking. If not specified, will use the first camera called with the subscribe() method. --- # sl::PositionalTrackingLidarParameters **Module:** **Lidar Module** Structure containing the options used to enable positional tracking with Lidar. `#include ` ## Public Attributes Documentation ### variable initial_world_transform ```cpp sl::Transform initial_world_transform; ``` Position of the camera in the world frame when the camera is started. Use this transform to place the camera frame in the world frame. Default: Identity matrix ### variable enable_real_time_computation ```cpp bool enable_real_time_computation = true; ``` Whether to compute the motion in real-time or not. Default: true ### variable voxel_size ```cpp float voxel_size = 0.0f; ``` Voxel size for the ICP. 0.0 means auto. Default: 0.0f --- # sl::PositionalTrackingSensorsParameters `#include ` ## Public Attributes Documentation ### variable initial_world_transforms ```cpp BatchedData< Transform > initial_world_transforms; ``` Position of the camera in the world frame when the camera is started. **Note**: The camera frame (which defines the reference frame for the camera) is by default positioned at the world frame when tracking is started. Use this sl::Transform to place the camera frame in the world frame. Default: Identity matrix. ### variable enable_area_memory ```cpp bool enable_area_memory = true; ``` Whether the camera can remember its surroundings. **Warning**: * This mode requires more resources to run, but greatly improves tracking accuracy. * We recommend leaving it on by default. This helps correct positional tracking drift and can be helpful for positioning different cameras relative to one other in space. Default: true ### variable enable_pose_smoothing ```cpp bool enable_pose_smoothing = false; ``` Whether to enable smooth pose correction for small drift correction. Default: false ### variable set_floor_as_origin ```cpp bool set_floor_as_origin = false; ``` Initializes the tracking to be aligned with the floor plane to better position the camera in space. **Note**: * This launches floor plane detection in the background until a suitable floor plane is found. * The tracking will start in sl::POSITIONAL_TRACKING_STATE::SEARCHING state. **Warning**: * This feature does not work with sl::MODEL::ZED since it needs an IMU to classify the floor. * The camera needs to look at the floor during initialization for optimum results. Default: false ### variable area_file_path ```cpp String area_file_path = String(); ``` Path of an area localization file that describes the surroundings (saved from a previous tracking session). **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. * The '.area' file can only be used with the same depth mode (sl::DEPTH_MODE) as the one used during area recording. Default: (empty) ### variable enable_imu_fusion ```cpp bool enable_imu_fusion = true; ``` Whether to enable the IMU fusion. **Note**: * This setting has no impact on the tracking of a camera. * sl::MODEL::ZED does not have an IMU. When set to false, only the optical odometry will be used. Default: true ### variable set_as_static ```cpp bool set_as_static = false; ``` 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`. All ZED SDK functionalities requiring positional tracking will be enabled without additional computation. sl::Camera::getPosition() will return the value set as `initial_world_transforms`. Default: false ### variable depth_min_range ```cpp float depth_min_range = -1.f; ``` 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) ### variable set_gravity_as_origin ```cpp bool set_gravity_as_origin = true; ``` Whether to override 2 of the 3 rotations from `initial_world_transforms` using the IMU gravity. **Note**: This parameter does nothing on sl::ZED::MODEL since it does not have an IMU. Default: true ### variable mode ```cpp POSITIONAL_TRACKING_MODE mode = POSITIONAL_TRACKING_MODE::GEN_3; ``` 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 ### variable enable_GNSS_fusion ```cpp bool enable_GNSS_fusion = false; ``` This attribute is responsible for enabling or not GNSS positional tracking fusion. ### variable gnss_calibration_parameters ```cpp GNSSCalibrationParameters gnss_calibration_parameters; ``` Control the VIO / GNSS calibration process. ### variable base_footprint_to_world_transform ```cpp Transform base_footprint_to_world_transform; ``` 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. **Note**: Base footprint is the coordinate frame attached to the projected baselink coordinate frame on the ground. It is generally a constant offset between baselink and the ground. Fusion uses the base footprint coordinate frame to determine where is the ground with respect to the tracked baselink position and orientation. baselink is the root coordinate frame of the robot. Fusion configuration file must give the position and orientation of each camera with respect to the baselink ### variable base_footprint_to_baselink_transform ```cpp Transform base_footprint_to_baselink_transform; ``` 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. **Note**: This transform is used by the Fusion to determine where is the ground with respect to the baselink coordinate frame which is the root coordinate frame of Fusion. ### variable tracking_camera_id ```cpp SensorDeviceIdentifier tracking_camera_id; ``` ID of the camera used for positional tracking. If not specified, will use the first camera called with the subscribe() method. --- # sl::RawBuffer **Module:** **Video Module** Zero-copy wrapper for native camera capture buffers. More... `#include ` ## Detailed Description ```cpp struct sl::RawBuffer; ``` Zero-copy wrapper for native camera capture buffers. **Note**: Currently only supports NVBUFSURFACE type (Argus native buffers). **Warning**: * Enabled by defining SL_ENABLE_ADVANCED_CAPTURE_API before including this header. Improper use can crash the Argus stack or destabilize the system. The RawBuffer does not free the underlying memory; it only releases the reference so that the capture system can reuse it. * **DO NOT manually destroy the NvBufSurface** (e.g., do not call NvBufSurfaceDestroy, NvBufSurfaceUnMap, etc.). The buffers are owned and managed by the SDK. Manual destruction will cause crashes or undefined behavior. This structure provides access to the raw NvBufSurface buffer without copying data. The buffer is automatically released when the RawBuffer goes out of scope or when release() is called, allowing the camera pipeline to reuse the buffer for the next capture. ```cpp #define SL_ENABLE_ADVANCED_CAPTURE_API #include Camera zed; InitParameters init_params; zed.open(init_params); while (true) { if (zed.grab() == ERROR_CODE::SUCCESS) { RawBuffer raw; if (zed.retrieveImage(raw) == ERROR_CODE::SUCCESS) { // Get NvBufSurface pointer directly void* nvbufLeft = raw.getRawBuffer(); // Returns left NvBufSurface void* nvbufRight = raw.getRawBufferRight(); // Returns right NvBufSurface // Cast to NvBufSurface* and use with Argus/NVMM APIs // auto* surf = static_cast(nvbufLeft); // raw is automatically released when going out of scope } } } ``` ## Public Functions Documentation ### function RawBuffer ```cpp RawBuffer() ``` Default constructor. ### function ~RawBuffer ```cpp ~RawBuffer() ``` Destructor - automatically releases the buffer. ### function RawBuffer ```cpp RawBuffer( RawBuffer && other ) ``` ### function operator= ```cpp RawBuffer & operator=( RawBuffer && other ) ``` ### function RawBuffer ```cpp RawBuffer( const RawBuffer & ) =delete ``` ### function operator= ```cpp RawBuffer & operator=( const RawBuffer & ) =delete ``` ### function getType ```cpp RAW_BUFFER_TYPE getType() const ``` Get the type of the raw buffer. **Return**: The buffer type (currently only NVBUFSURFACE is supported). ### function getRawBuffer ```cpp void * getRawBuffer() const ``` Get the left camera NvBufSurface pointer. **Return**: Pointer to the left NvBufSurface, or nullptr if not valid. **Note**: Cast to NvBufSurface* to use with Argus/NVMM APIs. **Warning**: **DO NOT destroy this buffer** (e.g., do not call NvBufSurfaceDestroy). The buffer is owned by the SDK. ### function getRawBufferRight ```cpp void * getRawBufferRight() const ``` Get the right camera NvBufSurface pointer. **Return**: Pointer to the right NvBufSurface, or nullptr if not valid. **Note**: Cast to NvBufSurface* to use with Argus/NVMM APIs. **Warning**: **DO NOT destroy this buffer** (e.g., do not call NvBufSurfaceDestroy). The buffer is owned by the SDK. ### function getTimestamp ```cpp uint64_t getTimestamp() const ``` Get the timestamp of the buffer. **Return**: Timestamp in nanoseconds. ### function getWidth ```cpp unsigned int getWidth() const ``` Get the width of the image. **Return**: Width in pixels. ### function getHeight ```cpp unsigned int getHeight() const ``` Get the height of the image. **Return**: Height in pixels. ### function isValid ```cpp bool isValid() const ``` Check if the buffer is valid and contains data. **Return**: true if the buffer is valid. ### function release ```cpp void release() ``` Manually release the buffer reference. **Note**: The buffer is automatically released when RawBuffer is destroyed. This allows the capture system to reuse the buffer. After calling this, the buffer is no longer valid. --- # sl::RecordingLidarParameters **Module:** **Lidar Module** Structure containing the options used to record Lidar data. `#include ` ## Public Attributes Documentation ### variable output_filename ```cpp std::string output_filename; ``` Path to the output file. ### variable format ```cpp RECORDING_FORMAT format = RECORDING_FORMAT::AUTO; ``` Format of the recording. Default: sl::RECORDING_FORMAT::AUTO. --- # sl::RecordingSensorsParameters `#include ` ## Public Attributes Documentation ### variable sensors_ids ```cpp std::set< sl::SensorDeviceIdentifier > sensors_ids = {}; ``` List of sensor id that will be used By default empty which means all available sensors in Sensors when the module is started. ### variable video_filenames ```cpp BatchedData< String > video_filenames; ``` Filename of the file to save the recording into. ### variable compression_mode ```cpp SVO_COMPRESSION_MODE compression_mode = SVO_COMPRESSION_MODE::H265; ``` Compression mode the recording. Default: sl::SVO_COMPRESSION_MODE::H265 ### variable bitrate ```cpp unsigned int bitrate = 0; ``` Overrides the default bitrate of the SVO file, in kbits/s. **Note**: * Only works if compression_mode is H264 or H265. * Available range: 0 or [1000 - 60000] Default: 0 (the default values associated with the resolution) ### variable target_framerate ```cpp unsigned int target_framerate = 0; ``` Framerate for the recording file. **Warning**: * This framerate must be below or equal to the camera framerate and camera framerate must be a multiple of the target framerate. * It means that it must respect ` camera_frameratetarget_framerate == 0`. * Allowed framerates are 15,30, 60 or 100 if possible. * Any other values will be discarded and camera FPS will be taken. Default: 0 (camera framerate will be taken) ### variable transcode_streaming_input ```cpp bool transcode_streaming_input = false; ``` Defines whether to decode and re-encode a streaming source. **Note**: * If set to false, it will avoid decoding/re-encoding and convert directly streaming input into a SVO file. * This saves an encoding session and can be especially useful on NVIDIA Geforce cards where the number of encoding session is limited. * compression_mode, target_framerate and bitrate will be ignored in this mode. Default: false --- # sl::RecordingStatus **Module:** **Video Module** Structure containing information about the status of the recording. `#include ` ## Public Functions Documentation ### function RecordingStatus ```cpp RecordingStatus() ``` Default constructor. Set all parameters to their default values. ## Public Attributes Documentation ### variable is_recording ```cpp bool is_recording; ``` Report if the recording has been enabled. ### variable is_paused ```cpp bool is_paused; ``` Report if the recording has been paused. ### variable status ```cpp bool status; ``` Status of current frame. True for success or false if the frame could not be written in the SVO file. ### variable current_compression_time ```cpp double current_compression_time; ``` Compression time for the current frame in milliseconds. ### variable current_compression_ratio ```cpp double current_compression_ratio; ``` Compression ratio (% of raw size) for the current frame. ### variable average_compression_time ```cpp double average_compression_time; ``` Average compression time in milliseconds since beginning of recording. ### variable average_compression_ratio ```cpp double average_compression_ratio; ``` Average compression ratio (% of raw size) since beginning of recording. ### variable number_frames_ingested ```cpp int number_frames_ingested; ``` Number of frames ingested in SVO encoding/writting. ### variable number_frames_encoded ```cpp int number_frames_encoded; ``` Number of frames effectively encoded and written. Might be different from the number of frames ingested. The difference will show the encoder latency. --- # sl::RegionOfInterestParameters `#include ` ## Public Attributes Documentation ### variable depth_far_threshold_meters ```cpp float depth_far_threshold_meters = 2.5; ``` Filtering how far object in the ROI should be considered, this is useful for a vehicle for instance. Default: 2.5 meters ### variable image_height_ratio_cutoff ```cpp float image_height_ratio_cutoff = 0.5; ``` 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 ### variable auto_apply_module ```cpp std::unordered_set< MODULE > auto_apply_module = {MODULE::ALL}; ``` Once computed the ROI computed will be automatically applied. Default: All modules --- # sl::Resolution **Module:** **Core Module** Structure containing the width and height of an image. `#include ` ## Public Functions Documentation ### function Resolution ```cpp inline Resolution( int w_ =0, int h_ =0 ) ``` Default constructor. ### function area ```cpp inline int area() const ``` Returns the area (width * height) of the image. ### function operator== ```cpp inline bool operator==( const Resolution & that ) const ``` Tests if the given sl::Resolution has the same properties. **Return**: True if the sizes matches. ### function operator!= ```cpp inline bool operator!=( const Resolution & that ) const ``` Tests if the given sl::Resolution has different properties. **Return**: True if the sizes are not equal. ### function encode ```cpp bool encode( String & serialized_content ) const ``` Generate a JSON Object (with the struct type as a key) containing the serialized struct, converted into a string. **Parameters**: * **serialized_content** output string containing the JSON Object **Return**: True if file was successfully saved, otherwise false. ### function decode ```cpp bool decode( const String & serialized_content ) ``` Fill the structure from the serialized json object contained in the input string. **Parameters**: * **serialized_content** input string containing the JSON Object **Return**: True if the decoding was successful, otherwise false. ## Public Attributes Documentation ### variable width ```cpp int width; ``` Width of the image in pixels. ### variable height ```cpp int height; ``` Height of the image in pixels. --- # sl::RuntimeSensorsParameters `#include ` ## Public Attributes Documentation ### variable depth_confidence_threshold ```cpp BatchedData< int > depth_confidence_threshold = { {defaultSensorDeviceIdentifier(), 95} }; ``` Depth confidence threshold for each sensor. Default: 95 for all sensors. ### variable reference_frame ```cpp SENSORS_REFERENCE_FRAME reference_frame = SENSORS_REFERENCE_FRAME::SENSOR; ``` 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). --- # sl::SVOData `#include ` ## Public Functions Documentation ### function SVOData ```cpp inline SVOData( std::string & key_, std::vector< uint8_t > & content_, sl::Timestamp timestamp_ns_ =0 ) ``` ### function SVOData ```cpp inline SVOData() ``` ### function setContent ```cpp inline bool setContent( const std::string & s ) ``` Set a std::string into the SVOData's content. ### function getContent ```cpp inline bool getContent( std::string & s ) const ``` Retrieve the SVOData content as a std::string. ## Public Attributes Documentation ### variable key ```cpp std::string key; ``` ### variable timestamp_ns ```cpp sl::Timestamp timestamp_ns = 0; ``` ### variable content ```cpp std::vector< uint8_t > content; ``` --- # sl::SensorList **Module:** **Sensors Module** Structure containing lists of all available sensor devices. More... `#include ` ## Detailed Description ```cpp struct sl::SensorList; ``` Structure containing lists of all available sensor devices. **Note**: Use Sensors::getSensorList() to retrieve this information. 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 ## Public Attributes Documentation ### variable cameras ```cpp std::vector< DeviceProperties > cameras; ``` List of connected ZED stereo cameras (ZED, ZED 2, ZED 2i, ZED X, ZED X Mini). ### variable cameras_one ```cpp std::vector< DeviceProperties > cameras_one; ``` List of connected ZED One cameras. ### variable lidars ```cpp std::vector< LidarDeviceProperties > lidars; ``` List of connected Lidar devices. --- # sl::SensorParameters **Module:** **Core Module** Structure containing information about a single sensor available in the current device. More... `#include ` ## Detailed Description ```cpp struct sl::SensorParameters; ``` Structure containing information about a single sensor available in the current device. **Note**: * This structure is meant to be used as a read-only container. * Editing any of its fields will not impact the ZED SDK. Information about the camera sensors is available in the sl::CameraInformation struct returned by sl::Camera.getCameraInformation(). ## Public Attributes Documentation ### variable type ```cpp sl::SENSOR_TYPE type; ``` Type of the sensor. ### variable resolution ```cpp float resolution; ``` Resolution of the sensor. ### variable sampling_rate ```cpp float sampling_rate; ``` Sampling rate (or ODR) of the sensor. ### variable range ```cpp sl::float2 range; ``` Range of the sensor (minimum: `range.x`, maximum: `range.y`). ### variable noise_density ```cpp float noise_density; ``` White noise density given as continuous (frequency-independent). **Note**: * The units will be expressed in `sensor_unit / √(Hz)`. * `NAN` if the information is not available. ### variable random_walk ```cpp float random_walk; ``` Random walk derived from the Allan Variance given as continuous (frequency-independent). **Note**: * The units will be expressed in `sensor_unit / √(Hz)`. * `NAN` if the information is not available. ### variable sensor_unit ```cpp sl::SENSORS_UNIT sensor_unit; ``` Unit of the sensor. ### variable isAvailable ```cpp bool isAvailable; ``` Whether the sensor is available in your camera. --- # sl::SensorsConfiguration **Module:** **Core Module** Structure containing information about all the sensors available in the current device. More... `#include ` ## Detailed Description ```cpp struct sl::SensorsConfiguration; ``` Structure containing information about all the sensors available in the current device. **Note**: * This structure is meant to be used as a read-only container. * Editing any of its fields will not impact the ZED SDK. Information about the camera sensors is available in the sl::CameraInformation struct returned by sl::Camera.getCameraInformation(). ## Public Functions Documentation ### function isSensorAvailable ```cpp bool isSensorAvailable( const sl::SENSOR_TYPE & sensor_type ) ``` Checks if a sensor is available on the device. **Parameters**: * **sensor_type** : Sensor type to check. **Return**: true if the sensor is available on the device, otherwise false. ## Public Attributes Documentation ### variable firmware_version ```cpp unsigned int firmware_version = 0; ``` Firmware version of the sensor module. **Note**: 0 if no sensors are available (sl::MODEL::ZED). ### variable camera_imu_transform ```cpp sl::Transform camera_imu_transform; ``` IMU to left camera transform matrix. **Note**: It contains the rotation and translation between the IMU frame and camera frame. ### variable imu_magnetometer_transform ```cpp sl::Transform imu_magnetometer_transform; ``` Magnetometer to IMU transform matrix. **Note**: It contains rotation and translation between IMU frame and magnetometer frame. ### variable accelerometer_parameters ```cpp sl::SensorParameters accelerometer_parameters; ``` Configuration of the accelerometer. ### variable gyroscope_parameters ```cpp sl::SensorParameters gyroscope_parameters; ``` Configuration of the gyroscope. ### variable magnetometer_parameters ```cpp sl::SensorParameters magnetometer_parameters; ``` Configuration of the magnetometer. ### variable barometer_parameters ```cpp sl::SensorParameters barometer_parameters; ``` Configuration of the barometer. --- # sl::SensorsData::BarometerData **Module:** **Core Module** Structure containing data from the barometer sensor. `#include ` ## Public Attributes Documentation ### variable is_available ```cpp bool is_available; ``` Whether the barometer sensor is available in your camera. ### variable timestamp ```cpp sl::Timestamp timestamp; ``` Data acquisition timestamp. ### variable pressure ```cpp float pressure; ``` Ambient air pressure in hectopascal (hPa). ### variable relative_altitude ```cpp float relative_altitude; ``` Relative altitude from first camera position (at sl::Camera.open() time). ### variable effective_rate ```cpp float effective_rate; ``` Realtime data acquisition rate in hertz (Hz). --- # sl::SensorsData::IMUData **Module:** **Core Module** Structure containing data from the IMU sensor. `#include ` ## Public Attributes Documentation ### variable is_available ```cpp bool is_available; ``` Whether the IMU sensor is available in your camera. ### variable timestamp ```cpp sl::Timestamp timestamp; ``` Data acquisition timestamp. ### variable pose ```cpp sl::Transform pose; ``` IMU pose (IMU 6-DoF fusion). ### variable pose_covariance ```cpp sl::Matrix3f pose_covariance; ``` Covariance matrix of the IMU pose (pose). ### variable angular_velocity ```cpp sl::float3 angular_velocity; ``` Angular velocity vector of the gyroscope in deg/s. **Note**: * The value can be directly ingested in an IMU fusion algorithm to extract a quaternion. * Not available in SVO or STREAM mode. The value is corrected from bias, scale and misalignment. ### variable linear_acceleration ```cpp sl::float3 linear_acceleration; ``` Linear acceleration vector of the gyroscope in m/s². **Note**: * The value can be directly ingested in an IMU fusion algorithm to extract a quaternion. * Not available in SVO or STREAM mode. The value is corrected from bias, scale and misalignment. ### variable angular_velocity_uncalibrated ```cpp sl::float3 angular_velocity_uncalibrated; ``` Angular velocity vector of the gyroscope in deg/s (uncorrected from the IMU calibration). **Note**: * The value is the exact raw values from the IMU. * Not available in SVO or STREAM mode. ### variable linear_acceleration_uncalibrated ```cpp sl::float3 linear_acceleration_uncalibrated; ``` Linear acceleration vector of the gyroscope in m/s² (uncorrected from the IMU calibration). **Note**: * The value is the exact raw values from the IMU. * Not available in SVO or STREAM mode. ### variable angular_velocity_covariance ```cpp sl::Matrix3f angular_velocity_covariance; ``` Covariance matrix of the angular velocity of the gyroscope in deg/s (angular_velocity). **Note**: Not available in SVO or STREAM mode. ### variable linear_acceleration_covariance ```cpp sl::Matrix3f linear_acceleration_covariance; ``` Covariance matrix of the linear acceleration of the gyroscope in m/s² (linear_acceleration). **Note**: Not available in SVO or STREAM mode. ### variable effective_rate ```cpp float effective_rate; ``` Realtime data acquisition rate in hertz (Hz). --- # sl::SensorsData::MagnetometerData **Module:** **Core Module** Structure containing data from the magnetometer sensor. `#include ` ## Public Types Documentation ### enum HEADING_STATE | Enumerator | Value | Description | | ---------- | ----- | ----------- | | 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. | Lists the different states of the magnetic heading. ## Public Attributes Documentation ### variable is_available ```cpp bool is_available; ``` Whether the magnetometer sensor is available in your camera. ### variable timestamp ```cpp sl::Timestamp timestamp; ``` Data acquisition timestamp. ### variable magnetic_field_uncalibrated ```cpp sl::float3 magnetic_field_uncalibrated; ``` Uncalibrated magnetic field local vector in microtesla (μT). **Note**: * The magnetometer raw values are affected by soft and hard iron interferences. * The sensor must be calibrated by placing the camera in the working environment and using **ZED****Sensor****Viewer** tool. * Not available in SVO or STREAM mode. ### variable magnetic_field_calibrated ```cpp sl::float3 magnetic_field_calibrated; ``` 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. ### variable magnetic_heading ```cpp float magnetic_heading; ``` 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. * To get a correct magnetic heading, the magnetometer sensor must be calibrated using **ZED****Sensor****Viewer** tool. ### variable magnetic_heading_state ```cpp HEADING_STATE magnetic_heading_state; ``` State of magnetic_heading. ### variable magnetic_heading_accuracy ```cpp float magnetic_heading_accuracy; ``` 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. ### variable effective_rate ```cpp float effective_rate; ``` Realtime data acquisition rate in hertz (Hz). --- # sl::SensorsData::TemperatureData **Module:** **Core Module** Structure containing data from the temperature sensors. `#include ` ## Public Types Documentation ### enum SENSOR_LOCATION | Enumerator | Value | Description | | ---------- | ----- | ----------- | | 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. | Lists possible locations of temperature sensors. ## Public Functions Documentation ### function get ```cpp ERROR_CODE get( SENSOR_LOCATION location, float & temperature ) ``` Gets the temperature value at a temperature sensor location. **Parameters**: * **location** : Location of the temperature sensor to request. * **temperature** : Reference to the temperature value to be filled. **Return**: Temperature in °C at the requested location. ## Public Attributes Documentation ### variable temperature_map ```cpp std::map< SENSOR_LOCATION, float > temperature_map; ``` Map storing the temperatures at the different temperature sensors location. --- # sl::Sensors::ImplDeleter ## Public Functions Documentation ### function operator() ```cpp void operator()( SensorsMemberHandler * ptr ) ``` --- # sl::SpatialMappingFusionParameters **Module:** **Fusion Module** Sets the spatial mapping parameters. More... `#include ` ## Detailed Description ```cpp class sl::SpatialMappingFusionParameters; ``` Sets the spatial mapping parameters. **Note**: Users can adjust these parameters as they see fit. Instantiating with the default constructor will set all parameters to their default values. You can customize these values to fit your application, and then save them to a preset to be loaded in future executions. ## Public Functions Documentation ### function set ```cpp void set( SpatialMappingParameters::MAPPING_RESOLUTION mapping_resolution =SpatialMappingParameters::MAPPING_RESOLUTION::MEDIUM ) ``` Sets the resolution corresponding to the given SpatialMappingParameters::MAPPING_RESOLUTION preset. **Parameters**: * **mapping_resolution** The desired SpatialMappingParameters::MAPPING_RESOLUTION. Default: [SpatialMappingParameters::MAPPING_RESOLUTION::MEDIUM]. ### function set ```cpp void set( SpatialMappingParameters::MAPPING_RANGE mapping_range =SpatialMappingParameters::MAPPING_RANGE::MEDIUM ) ``` Sets the maximum value of the depth corresponding to the given SpatialMappingParameters::MAPPING_RANGE preset. **Parameters**: * **mapping_range** The desired SpatialMappingParameters::MAPPING_RANGE. Default: [SpatialMappingParameters::MAPPING_RANGE::MEDIUM]. ## Public Attributes Documentation ### variable resolution_meter ```cpp float resolution_meter = 0.05f; ``` Spatial mapping resolution in meters. ### variable range_meter ```cpp float range_meter = 0.f; ``` Depth range in meters. Can be different from the value set by sl::InitParameters::depth_maximum_distance. 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. ### variable use_chunk_only ```cpp bool use_chunk_only = false; ``` 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. ### variable max_memory_usage ```cpp int max_memory_usage = 2048; ``` The maximum CPU memory (in MB) allocated for the meshing process. ### variable disparity_std ```cpp float disparity_std = 0.3; ``` 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. ### variable decay ```cpp float decay = 1; ``` Adjust the weighting factor for the current depth during the integration process. By default, the value is set to 1, which results in the complete integration and fusion of the current depth with the previously integrated depth. Setting it to 0 discards all previous data and solely integrates the current depth. ### variable enable_forget_past ```cpp bool enable_forget_past = false; ``` ### variable stability_counter ```cpp int stability_counter = 0; ``` 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 value is 0, this will define the stability counter based on the mesh resolution, the higher the resolution, the higher the stability counter. ### variable map_type ```cpp SpatialMappingParameters::SPATIAL_MAP_TYPE map_type = SpatialMappingParameters::SPATIAL_MAP_TYPE::MESH; ``` 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 SpatialMappingParameters::SPATIAL_MAP_TYPE. --- # sl::SpatialMappingParameters **Module:** **Spatial Mapping Module** Structure containing a set of parameters for the spatial mapping module. More... `#include ` ## Detailed Description ```cpp class sl::SpatialMappingParameters; ``` Structure containing a set of parameters for the spatial mapping module. **Note**: Parameters can be adjusted by the user. The default constructor sets all parameters to their default settings. ## Public Types Documentation ### enum SPATIAL_MAP_TYPE | Enumerator | Value | Description | | ---------- | ----- | ----------- | | 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. | Lists the types of spatial maps that can be created. ### enum MAPPING_RESOLUTION | Enumerator | Value | Description | | ---------- | ----- | ----------- | | 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. | Lists the spatial mapping resolution presets. ### enum MAPPING_RANGE | Enumerator | Value | Description | | ---------- | ----- | ----------- | | 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. | Lists the spatial mapping depth range presets. ### typedef interval ```cpp typedef std::pair interval; ``` Float pair defining an interval. ## Public Functions Documentation ### function SpatialMappingParameters ```cpp SpatialMappingParameters( MAPPING_RESOLUTION resolution =MAPPING_RESOLUTION::MEDIUM, MAPPING_RANGE range =MAPPING_RANGE::AUTO, int max_memory_usage_ =2048, bool save_texture_ =false, bool use_chunk_only_ =false, bool reverse_vertex_order_ =false, SPATIAL_MAP_TYPE map_type =SPATIAL_MAP_TYPE::MESH, int stability_counter =0, float disparity_std =0.3f, float decay =1.f, bool enable_forget_past =false ) ``` Default constructor. Sets all parameters to their default and optimized values. ### function set ```cpp void set( MAPPING_RESOLUTION mapping_resolution =MAPPING_RESOLUTION::MEDIUM ) ``` Sets the resolution to a sl::SpatialMappingParameters::MAPPING_RESOLUTION preset. **Parameters**: * **mapping_resolution** The desired MAPPING_RESOLUTION. Default: MAPPING_RESOLUTION::MEDIUM ### function set ```cpp void set( MAPPING_RANGE mapping_range =MAPPING_RANGE::MEDIUM ) ``` Sets the range to a sl::SpatialMappingParameters::MAPPING_RANGE preset. **Parameters**: * **mapping_range** The desired MAPPING_RANGE. Default: MAPPING_RANGE::MEDIUM ### function get ```cpp static float get( MAPPING_RESOLUTION mapping_resolution =MAPPING_RESOLUTION::MEDIUM ) ``` Returns the value corresponding to a sl::SpatialMappingParameters::MAPPING_RESOLUTION preset in meters. **Parameters**: * **mapping_resolution** The desired MAPPING_RESOLUTION. Default: MAPPING_RESOLUTION::MEDIUM **Return**: The value of **mapping_resolution** in meters. ### function get ```cpp static float get( MAPPING_RANGE mapping_range =MAPPING_RANGE::MEDIUM ) ``` Returns the value corresponding to a sl::SpatialMappingParameters::MAPPING_RANGE preset in meters. **Parameters**: * **mapping_range** The desired MAPPING_RANGE. Default: MAPPING_RANGE::MEDIUM **Return**: The value of **mapping_range** in meters. ### function getRecommendedRange ```cpp static float getRecommendedRange( MAPPING_RESOLUTION mapping_resolution, Camera & camera ) ``` Returns the recommended maximum depth value corresponding to a sl::SpatialMappingParameters::MAPPING_RESOLUTION preset. **Parameters**: * **mapping_resolution** The desired MAPPING_RESOLUTION. * **camera** The Camera object that will run the spatial mapping. **Return**: The maximum value of the depth in meters. ### function getRecommendedRange ```cpp static float getRecommendedRange( float resolution_meters, Camera & camera ) ``` Returns the recommended maximum depth value for the given resolution in meters. **Parameters**: * **resolution_meters** The desired resolution in meters. * **camera** The Camera object that will run the spatial mapping. **Return**: The maximum value of the depth in meters. ## Public Attributes Documentation ### variable resolution_meter ```cpp float resolution_meter = 0.05f; ``` Spatial mapping resolution in meters. **Note**: It should fit allowed_resolution. ### variable range_meter ```cpp float range_meter = 0.f; ``` Depth range in meters. **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. Can be different from the value set by sl::InitParameters::depth_maximum_distance. ### variable save_texture ```cpp bool save_texture = false; ``` Whether to save the texture. **Note**: * This option will consume more memory. * This option is only available for [[sl::SpatialMappingParameters::SPATIAL_MAP_TYPE::MESH]](SpatialMappingParameters::SPATIAL_MAP_TYPE). If set to true, you will be able to apply the texture to your mesh after it is created. ### variable use_chunk_only ```cpp bool use_chunk_only = false; ``` Whether to only use chunks. **Note**: * Updating the mesh is time-consuming. * Setting this to true results in better performance. If set to false, you will ensure consistency between the mesh and its inner chunk data. ### variable max_memory_usage ```cpp int max_memory_usage = 2048; ``` The maximum CPU memory (in MB) allocated for the meshing process. ### variable reverse_vertex_order ```cpp bool reverse_vertex_order = false; ``` Whether to inverse the order of the vertices of the triangles. **Note**: This option is only available for [[sl::SpatialMappingParameters::SPATIAL_MAP_TYPE::MESH]](SpatialMappingParameters::SPATIAL_MAP_TYPE). If your display process does not handle front and back face culling, you can use this to correct it. ### variable map_type ```cpp SPATIAL_MAP_TYPE map_type = SPATIAL_MAP_TYPE::MESH; ``` 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::SpatialMappingParameters::SPATIAL_MAP_TYPE. ### variable stability_counter ```cpp int stability_counter = 0; ``` 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) ### variable disparity_std ```cpp float disparity_std = 0.3; ``` 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. ### variable decay ```cpp float decay = 1; ``` Adjust the weighting factor for the current depth during the integration process. By default, the value is set to 1, which results in the complete integration and fusion of the current depth with the previously integrated depth. Setting it to 0 discards all previous data and solely integrates the current depth. ### variable enable_forget_past ```cpp bool enable_forget_past = false; ``` This parameter enables the forgetting of the previous map to limit memory and drift issues. It enables a local spatial mapping that only keeps a mapped scene around the current camera position. The distance threshold is set to be equal to 1.5 x the range of the spatial mapping. ### variable allowed_resolution ```cpp static const interval allowed_resolution; ``` The resolution allowed by the spatial mapping: * **allowed_resolution.first** is the minimum value allowed * **allowed_resolution.second** is the maximum value allowed ### variable allowed_range ```cpp static const interval allowed_range; ``` The maximum depth allowed by spatial mapping: * **allowed_range.first** is the minimum value allowed * **allowed_range.second** is the maximum value allowed --- # sl::StreamingProperties **Module:** **Video Module** Structure containing information about the properties of a streaming device. `#include ` ## Public Attributes Documentation ### variable ip ```cpp sl::String ip = ""; ``` IP address of the streaming device. Default: "" ### variable port ```cpp unsigned short port = 0; ``` Streaming port of the streaming device. Default: 0 ### variable serial_number ```cpp unsigned int serial_number = 0; ``` Serial number of the streaming camera. Default: 0 ### variable current_bitrate ```cpp int current_bitrate = 0; ``` Current bitrate of encoding of the streaming device. Default: 0 ### variable camera_model ```cpp sl::MODEL camera_model = sl::MODEL::LAST; ``` Model of the streaming device. Default: LAST ### variable codec ```cpp STREAMING_CODEC codec = STREAMING_CODEC::H265; ``` Current codec used for compression in streaming device. Default: sl::STREAMING_CODEC::H265 --- # sl::StreamingSensorList **Module:** **Sensors Module** Structure containing lists of all available streaming sensor devices. More... `#include ` ## Detailed Description ```cpp struct sl::StreamingSensorList; ``` Structure containing lists of all available streaming sensor devices. **Note**: Use Sensors::getStreamingSensorList() to retrieve this information. 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 ## Public Attributes Documentation ### variable cameras ```cpp std::vector< StreamingProperties > cameras; ``` List of streaming ZED stereo cameras (ZED, ZED 2, ZED 2i, ZED X, ZED X Mini). ### variable cameras_one ```cpp std::vector< StreamingProperties > cameras_one; ``` List of streaming ZED One cameras. ### variable lidars ```cpp std::vector< LidarDeviceProperties > lidars; ``` List of streaming Lidar devices. --- # sl::StreamingSensorsParameters `#include ` ## Public Attributes Documentation ### variable sensors_ids ```cpp std::set< sl::SensorDeviceIdentifier > sensors_ids = {}; ``` List of sensor id that will be used By default empty which means all available sensors in Sensors when the module is started. ### variable codec ```cpp STREAMING_CODEC codec = STREAMING_CODEC::H265; ``` Encoding used for streaming. ### variable port ```cpp unsigned short port = 30000; ``` Port used for streaming. **Warning**: * Port must be an even number. Any odd number will be rejected. * Port must be opened. ### variable bitrate ```cpp unsigned int bitrate = 0; ``` Streaming bitrate (in Kbits/s) used for streaming. **Note**: Available range: [1000 - 60000] | sl::STREAMING_CODEC | sl::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) ### variable gop_size ```cpp int gop_size = -1; ``` GOP size in number of frames. **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. * Maximum value: 256 Default: -1 (the GOP size will last at maximum 2 seconds, depending on camera FPS) ### variable adaptative_bitrate ```cpp bool adaptative_bitrate = false; ``` Defines whether the adaptive bitrate is enabled. **Note**: * Bitrate will be adjusted depending the number of packet dropped during streaming. * 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). Default: false ### variable chunk_size ```cpp unsigned short chunk_size = 16084; ``` Size of a single chunk. **Note**: * Stream buffers are divided into X number of chunks where each chunk is chunk_size bytes long. * You can lower chunk_size value if network generates a lot of packet loss: this will generate more chunks for a single image, but each chunk sent will be lighter to avoid corruption within the chunk. * Increasing this value can decrease latency. * Available range: [1024 - 65000] Default: 16084 ### variable target_framerate ```cpp unsigned int target_framerate = 0; ``` Framerate for the streaming output. **Warning**: * This framerate must be below or equal to the camera framerate. * Allowed framerates are 15, 30, 60 or 100 if possible. * Any other values will be discarded and camera FPS will be taken. Default: 0 (camera framerate will be taken) --- # sl::SynchronizationParameter Configuration parameters for data synchronization. More... `#include ` ## Detailed Description ```cpp struct sl::SynchronizationParameter; ``` Configuration parameters for data synchronization. The SynchronizationParameter struct represents the configuration parameters used by the synchronizer. It allows customization of the synchronization process based on specific requirements. ## Public Functions Documentation ### function save ```cpp bool save( String filename ) const ``` Saves the current set of parameters into a file to be reloaded with the load() method. **Parameters**: * **filename** : Name of the file which will be created to store the parameters (extension '.json' 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. * In case a file already exists, the method will return false and existing file will not be updated. ### function load ```cpp bool load( String filename ) ``` Loads a set of parameters from the values contained in a previously saved file. **Parameters**: * **filename** : Path to the file from which the parameters will be loaded (extension '.json' will be added at the end of the filename if not detected). **Return**: True if the file was successfully loaded, otherwise false. ### function encode ```cpp bool encode( String & serialized_content ) const ``` Generate a JSON Object (with the struct type as a key) containing the serialized struct, converted into a string. **Parameters**: * **serialized_content** output string containing the JSON Object **Return**: True if file was successfully saved, otherwise false. ### function decode ```cpp bool decode( const String & serialized_content ) ``` Fill the structure from the serialized json object contained in the input string. **Parameters**: * **serialized_content** input string containing the JSON Object **Return**: True if the decoding was successful, otherwise false. ### function operator== ```cpp bool operator==( const SynchronizationParameter & param1 ) const ``` Comparison operator ==. **Parameters**: * **param1** to compare **Return**: true if the two struct are identical ### function operator!= ```cpp bool operator!=( const SynchronizationParameter & param1 ) const ``` Comparison operator !=. **Parameters**: * **param1** to compare **Return**: true if the two struct are different ## Public Attributes Documentation ### variable windows_size ```cpp double windows_size = 0; ``` 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 mean `grab()` duration of the camera at the lowest FPS. If not provided, the fusion SDK will compute it from the data's sources. Default value: 0 ### variable data_source_timeout ```cpp double data_source_timeout = 1000; ``` Duration in milliseconds before considering a camera as inactive if no more data is present (for example camera disconnection). The data_source_timeout parameter specifies the duration to wait before considering a camera as inactive if no new data is received within the specified time frame. Default value: 1000 ### variable keep_last_data ```cpp bool keep_last_data = false; ``` 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. Default value: false ### variable maximum_lateness ```cpp double maximum_lateness = 50; ``` 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. Default value: 50 --- # sl::TensorParameters **Module:** **Core Module** Structure to define the input options for deep learning inference. `#include ` ## Public Types Documentation ### enum COLOR_FORMAT | Enumerator | Value | Description | | ---------- | ----- | ----------- | | GRAY | | 1-channel Grayscale. | | Y | | 1-channel Y (Luminance) from YUV. | | RGB | | 3-channel RGB. | | BGR | | 3-channel BGR. | | RGBA | | 4-channel RGBA. | | BGRA | | 4-channel BGRA. | Lists available color formats for the Tensor. ### enum LAYOUT | Enumerator | Value | Description | | ---------- | ----- | ----------- | | NCHW | | Batch, Channels, Height, Width (Planar). Common for PyTorch models. | | NHWC | | Batch, Height, Width, Channels (Interleaved). Common for TensorFlow models. | Lists available memory layouts for the Tensor. ### enum PIXEL_TYPE | Enumerator | Value | Description | | ---------- | ----- | ----------- | | FLOAT | 0| 32-bit floating point. | | HALF | 1| 16-bit floating point (half precision). | | UCHAR | 2| Unsigned char (8-bit). | Lists available pixel data types for the Tensor elements. ## Public Functions Documentation ### function getPixelSize ```cpp inline size_t getPixelSize() const ``` 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). ### function getRequestedChannels ```cpp inline int getRequestedChannels() const ``` Returns the number of channels associated with the color_format. **Return**: The number of channels. ## Public Attributes Documentation ### variable target_size ```cpp sl::Resolution target_size = sl::Resolution(640, 640); ``` Target size for the input image (Width, Height). ### variable pixel_type ```cpp PIXEL_TYPE pixel_type = PIXEL_TYPE::FLOAT; ``` Pixel data type for the Tensor elements. **Note**: Specifies the underlying data type: UCHAR (8-bit), FLOAT (32-bit), or HALF (16-bit). ### variable mean ```cpp sl::float3 mean = {0.485f, 0.456f, 0.406f}; ``` Normalization parameter: Mean. **Note**: * Pixel = (Pixel * Scale - Mean) / Std. * Default: ImageNet Standard {0.485, 0.456, 0.406}. ### variable std ```cpp sl::float3 std = {0.229f, 0.224f, 0.225f}; ``` Normalization parameter: Standard Deviation. **Note**: * Pixel = (Pixel * Scale - Mean) / Std. * Default: ImageNet Standard {0.229, 0.224, 0.225}. ### variable stretch ```cpp bool stretch = false; ``` If true, stretches the image to target_size. If false, keeps aspect ratio and applies letterboxing (padding). ### variable scale ```cpp sl::float3 scale = {1.f / 255.f, 1.f / 255.f, 1.f / 255.f}; ``` Scale factor applied to the pixel values before normalization. ### variable color_format ```cpp COLOR_FORMAT color_format = COLOR_FORMAT::BGR; ``` Desired color format for the output Tensor. ### variable layout ```cpp LAYOUT layout = LAYOUT::NCHW; ``` Desired memory layout for the output Tensor. **Note**: * NCHW (planar) is common for PyTorch models. * NHWC (interleaved) is common for TensorFlow models. ### variable batch_size ```cpp size_t batch_size = 1; ``` Number of images in the batch. ### variable memory_type ```cpp MEM memory_type = MEM::GPU; ``` Where the Tensor should be stored (CPU or GPU). --- # sl::Timestamp **Module:** **Core Module** Structure representing timestamps with utilities. `#include ` ## Public Functions Documentation ### function Timestamp ```cpp inline Timestamp() ``` Default constructor. Initialized the sl::Timestamp instance to 0. ### function Timestamp ```cpp inline Timestamp( uint64_t _data_ns ) ``` Initialized the sl::Timestamp instance to a number in nanoseconds. ### function getNanoseconds ```cpp inline uint64_t getNanoseconds() const ``` Returns the timestamp in nanoseconds. ### function getMicroseconds ```cpp inline uint64_t getMicroseconds() const ``` Returns the timestamp in microseconds. ### function getMilliseconds ```cpp inline uint64_t getMilliseconds() const ``` Returns the timestamp in milliseconds. ### function getSeconds ```cpp inline uint64_t getSeconds() const ``` Returns the timestamp in seconds. ### function setNanoseconds ```cpp inline void setNanoseconds( uint64_t t_ns ) ``` Sets the timestamp to a value in nanoseconds. ### function setMicroseconds ```cpp inline void setMicroseconds( uint64_t t_us ) ``` Sets the timestamp to a value in microseconds. ### function setMilliseconds ```cpp inline void setMilliseconds( uint64_t t_ms ) ``` Sets the timestamp to a value in milliseconds. ### function setSeconds ```cpp inline void setSeconds( uint64_t t_s ) ``` Sets the timestamp to a value in seconds. ### function operator= ```cpp inline Timestamp & operator=( Timestamp other ) ``` Copy the value of another sl::Timestamp. ### function operator= ```cpp inline Timestamp & operator=( uint64_t other_data_ns ) ``` Sets the value of the sl::Timestamp to **other_data_ns**. ### function operator+= ```cpp inline Timestamp & operator+=( const Timestamp & rhs ) ``` Adds the value of another sl::Timestamp to the current one. ### function operator-= ```cpp inline Timestamp & operator-=( const Timestamp & rhs ) ``` Subtracts the value of another sl::Timestamp to the current one. ### function operator*= ```cpp inline Timestamp & operator*=( const Timestamp & rhs ) ``` Multiplies the value of another sl::Timestamp to the current one. ### function operator/= ```cpp inline Timestamp & operator/=( const Timestamp & rhs ) ``` Divides the value of the current sl::Timestamp by another one. ### function operator unsigned long long int ```cpp inline operator unsigned long long int() const ``` Convert the sl::Timestamp into a unsigned long long int. ### function fromNanoseconds ```cpp static inline Timestamp fromNanoseconds( uint64_t t_ns ) ``` Create a Timestamp from nanoseconds. ### function fromMicroseconds ```cpp static inline Timestamp fromMicroseconds( uint64_t t_us ) ``` Create a Timestamp from microseconds. ### function fromMilliseconds ```cpp static inline Timestamp fromMilliseconds( uint64_t t_ms ) ``` Create a Timestamp from milliseconds. ### function fromSeconds ```cpp static inline Timestamp fromSeconds( uint64_t t_s ) ``` Create a Timestamp from seconds. ## Public Attributes Documentation ### variable data_ns ```cpp uint64_t data_ns = 0; ``` Timestamp in nanoseconds. --- # sl::VoxelMeasureParameters **Module:** **Depth Sensing Module** Parameters controlling voxel decimation in sl::Camera::retrieveVoxelMeasure. More... `#include ` ## Detailed Description ```cpp struct sl::VoxelMeasureParameters; ``` Parameters controlling voxel decimation in sl::Camera::retrieveVoxelMeasure. A default-constructed instance uses stereo-adaptive mode, matching the stereo camera's noise model out of the box. ## Public Attributes Documentation ### variable voxel_size ```cpp float voxel_size = -1.f; ``` 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]. ### variable centroid ```cpp bool centroid = true; ``` Controls output point positions within each voxel. If true, output point positions are the centroid of all points in each voxel. If false, output positions are snapped to the voxel grid center. ### variable resolution_mode ```cpp VOXELIZATION_MODE resolution_mode = VOXELIZATION_MODE::STEREO_UNCERTAINTY; ``` How voxel size adapts with depth. * [VOXELIZATION_MODE::FIXED] : uniform voxel_size everywhere. * [VOXELIZATION_MODE::STEREO_UNCERTAINTY] : voxel grows as Z²/(f·B), matching stereo depth precision. * [VOXELIZATION_MODE::LINEAR] : voxel grows proportionally to Z. Focal length, baseline, and unit conversion are derived automatically from camera calibration. ### variable resolution_scale ```cpp float resolution_scale = 0.2f; ``` Scale factor for depth-adaptive voxel growth. Controls how aggressively voxels grow with depth. Larger values produce coarser voxels at distance (fewer points, better performance). Smaller values keep voxels tighter at range (more points, higher cost). Typical range: [0.01, 1.0]. Clamped internally to [0.01, 3.0]. **Note**: Only used when resolution_mode is not [VOXELIZATION_MODE::FIXED]. Silently ignored otherwise. --- # std::hash< sl::CameraIdentifier > `#include ` ## Public Functions Documentation ### function operator() ```cpp inline std::size_t operator()( const sl::CameraIdentifier & id ) const ``` --- # std::hash< sl::String > `#include ` ## Public Functions Documentation ### function operator() ```cpp inline std::size_t operator()( const sl::String & s ) const ``` --- # sl_zed/CameraOne.hpp ## Namespaces | Name | | -------------- | | **sl**
@HideINTERNAL_PUBLICAPI_START | ## Classes | | Name | | -------------- | -------------- | | class | **sl::InitParametersOne**
Class containing the options used to initialize the sl::CameraOne object. | | struct | **sl::CameraOneConfiguration**
Structure containing information about the camera sensor. | | struct | **sl::CameraOneInformation**
Structure containing information of a single camera (serial number, model, input type, etc.). | | class | **sl::CameraOne**
This class serves as the primary interface between the camera and the various features provided by the SDK when using Monocular cameras. | --- # sl_zed/Camera.hpp ## Namespaces | Name | | -------------- | | **sl**
@HideINTERNAL_PUBLICAPI_START | ## Classes | | Name | | -------------- | -------------- | | class | **sl::InitParameters**
Class containing the options used to initialize the sl::Camera object. | | struct | **sl::RuntimeParameters**
Structure containing parameters that defines the behavior of sl::Camera::grab(). | | class | **sl::PositionalTrackingParameters**
Structure containing a set of parameters for the positional tracking module initialization. | | struct | **sl::VoxelMeasureParameters**
Parameters controlling voxel decimation in sl::Camera::retrieveVoxelMeasure. | | class | **sl::SpatialMappingParameters**
Structure containing a set of parameters for the spatial mapping module. | | struct | **sl::StreamingParameters**
Structure containing the options used to stream with the ZED SDK. | | struct | **sl::RecordingParameters**
Structure containing the options used to record. | | struct | **sl::RawBuffer**
Zero-copy wrapper for native camera capture buffers. | | class | **sl::Camera**
This class serves as the primary interface between the camera and the various features provided by the SDK. | --- # utils/Core.hpp ## Namespaces | Name | | -------------- | | **sl**
@HideINTERNAL_PUBLICAPI_START | ## Classes | | Name | | -------------- | -------------- | | class | **sl::Mat**
Class representing 1 to 4-channel matrix of float or uchar, stored on CPU and/or GPU side. | | struct | **sl::TensorParameters**
Structure to define the input options for deep learning inference. | | class | **sl::Tensor**
Class representing a multi-dimensional array (Tensor), typically used for deep learning inference. | | class | **sl::Rotation**
Class representing a rotation for the positional tracking module. | | class | **sl::Translation**
Class representing a translation for the positional tracking module. | | class | **sl::Orientation**
Class representing an orientation/quaternion for the positional tracking module. | | class | **sl::Transform**
Class representing a transformation (translation and rotation) for the positional tracking module. | | struct | **sl::CalibrationParameters**
Structure containing intrinsic and extrinsic parameters of the camera (translation and rotation). | | struct | **sl::SensorParameters**
Structure containing information about a single sensor available in the current device. | | struct | **sl::SensorsConfiguration**
Structure containing information about all the sensors available in the current device. | | struct | **sl::CameraConfiguration**
Structure containing information about the camera sensor. | | struct | **sl::CameraInformation**
Structure containing information of a single camera (serial number, model, input type, etc.). | | class | **sl::Pose**
Class containing positional tracking data giving the position and orientation of the camera in 3D space. | | class | **sl::Landmark**
Represents a 3d landmark. | | class | **sl::Landmark2D**
Represents the projection of a 3d landmark in the image. | | class | **sl::KeyFrame**
Represents a keyframe in the tracking system. | | struct | **sl::SensorsData**
Structure containing all sensors data (except image sensors) to be used for positional tracking or environment study. | | struct | **sl::SensorsData::BarometerData**
Structure containing data from the barometer sensor. | | struct | **sl::SensorsData::TemperatureData**
Structure containing data from the temperature sensors. | | struct | **sl::SensorsData::MagnetometerData**
Structure containing data from the magnetometer sensor. | | struct | **sl::SensorsData::IMUData**
Structure containing data from the IMU sensor. | | class | **sl::ObjectData**
Class containing data of a detected object such as its bounding_box, label, id and its 3D position. | | class | **sl::CustomBoxObjectData**
Class that store externally detected objects. | | class | **sl::CustomMaskObjectData**
Class that store externally detected objects with mask. | | class | **sl::Objects**
Class containing the results of the object detection module. | | class | **sl::BodyData**
Class containing data of a detected body/person such as its bounding_box, id and its 3D position. | | class | **sl::Bodies**
Class containing the results of the body tracking module. | | class | **sl::ObjectsBatch**
Class containing batched data of a detected objects from the object detection module. | | class | **sl::BodiesBatch**
Class containing batched data of a detected bodies/persons from the body tracking module. | | class | **sl::CommunicationParameters**
Holds the communication parameter to configure the connection between senders and receiver. | | struct | **sl::SVOData** | | struct | **sl::HealthStatus** | | class | **sl::PositionalTrackingStatus**
Lists the different status of positional tracking. | | class | **sl::BatchParameters**
Structure containing a set of parameters for batch object detection. | | class | **sl::ObjectDetectionParameters**
Structure containing a set of parameters for the object detection module. | | class | **sl::ObjectTrackingParameters**
Structure containing a set of parameters for the object tracking module. | | class | **sl::ObjectDetectionRuntimeParameters**
Structure containing a set of runtime parameters for the object detection module. | | class | **sl::CustomObjectDetectionProperties**
Structure containing a set of runtime properties of a certain class ID for the object detection module using a custom model. | | class | **sl::CustomObjectDetectionRuntimeParameters**
Structure containing a set of runtime parameters for the object detection module using your own model ran by the SDK. | | struct | **sl::BodyTrackingParameters**
Structure containing a set of parameters for the body tracking module. | | struct | **sl::BodyTrackingRuntimeParameters**
Structure containing a set of runtime parameters for the body tracking module. | | class | **sl::PlaneDetectionParameters**
Structure containing a set of parameters for the plane detection functionality. | | struct | **sl::RegionOfInterestParameters** | | class | **sl::ECEF**
Represents a world position in ECEF format. | | class | **sl::LatLng**
Represents a world position in LatLng format. | | class | **sl::UTM**
Represents a world position in UTM format. | | class | **sl::ENU**
Represents a world position in ENU format. | | class | **sl::GeoConverter**
Purely static class for Geo functions. | | class | **sl::GeoPose**
Holds geographic reference position information. | | class | **sl::GNSSData**
Class containing GNSS data to be used for positional tracking as prior. | | class | **sl::FusedPositionalTrackingStatus**
Class containing the overall position fusion status. | | class | **sl::GNSSCalibrationParameters**
Holds the options used for calibrating GNSS / VIO. | --- # sl_fusion/Fusion.hpp ## Namespaces | Name | | -------------- | | **sl**
@HideINTERNAL_PUBLICAPI_START | | **std**
STL namespace. | ## Classes | | Name | | -------------- | -------------- | | class | **sl::CameraIdentifier**
Used to identify a specific camera in the Fusion API. | | class | **sl::FusionConfiguration**
Useful struct to store the Fusion configuration, can be read from /write to a JSON file. | | struct | **sl::SynchronizationParameter**
Configuration parameters for data synchronization. | | class | **sl::InitFusionParameters**
Holds the options used to initialize the Fusion object. | | class | **sl::BodyTrackingFusionParameters**
Holds the options used to initialize the body tracking module of the Fusion. | | class | **sl::BodyTrackingFusionRuntimeParameters**
Holds the options used to change the behavior of the body tracking module at runtime. | | class | **sl::ObjectDetectionFusionParameters**
Holds the options used to initialize the object detection module of the Fusion. | | class | **sl::PositionalTrackingFusionParameters**
Holds the options used for initializing the positional tracking fusion module. | | class | **sl::SpatialMappingFusionParameters**
Sets the spatial mapping parameters. | | class | **sl::CameraMetrics**
Holds the metrics of a sender in the fusion process. | | class | **sl::FusionMetrics**
Holds the metrics of the fusion process. | | class | **sl::Fusion**
Holds Fusion process data and functions. | | struct | **std::hash< sl::CameraIdentifier >** | --- # sl_lidar/Lidar.hpp ## Namespaces | Name | | -------------- | | **sl**
@HideINTERNAL_PUBLICAPI_START | ## Classes | | Name | | -------------- | -------------- | | struct | **sl::LidarCalibration**
Structure containing beam geometry calibration data for raw data processing. | | struct | **sl::LidarSensorConfiguration**
Structure containing runtime configuration of the Lidar sensor. | | struct | **sl::LidarInformation**
Structure containing information about the Lidar device. | | struct | **sl::LidarDeviceProperties**
Structure containing properties of a discovered Lidar device. | | class | **sl::InitLidarParameters**
Structure containing the options used to initialize the Lidar object. | | class | **sl::PositionalTrackingLidarParameters**
Structure containing the options used to enable positional tracking with Lidar. | | class | **sl::RecordingLidarParameters**
Structure containing the options used to record Lidar data. | | class | **sl::Lidar**
Class for Lidar control and data retrieval. It provides methods to initialize the Lidar, retrieve data, and enable positional tracking. Supports both live sensor input and OSF file playback. | --- # mapping/Mesh.hpp ## Namespaces | Name | | -------------- | | **sl**
@HideINTERNAL_PUBLICAPI_START | ## Classes | | Name | | -------------- | -------------- | | class | **sl::MeshFilterParameters**
Class containing a set of parameters for the mesh filtration functionality. | | class | **sl::Chunk**
Class representing a sub-mesh containing local vertices and triangles. | | class | **sl::Mesh**
Class representing a mesh and containing the geometric (and optionally texture) data of the scene captured by the spatial mapping module. | | class | **sl::Plane**
Class representing a plane defined by a point and a normal, or a plane equation. | | class | **sl::PointCloudChunk**
Class representing a sub-point cloud containing local vertices and colors. | | class | **sl::FusedPointCloud**
Class representing a fused point cloud and containing the geometric and color data of the scene captured by the spatial mapping module. | ## Defines | | Name | | -------------- | -------------- | | | **SL_SCANNING_EXPORT** | ## Macros Documentation ### define SL_SCANNING_EXPORT ```cpp #define SL_SCANNING_EXPORT ``` --- # sl_sensors/Sensors.hpp ## Namespaces | Name | | -------------- | | **sl**
@HideINTERNAL_PUBLICAPI_START | ## Classes | | Name | | -------------- | -------------- | | class | **sl::SensorDeviceIdentifier**
Structure containing information about a sensor device (camera or lidar) managed by the Sensors class. | | struct | **sl::InitSensorsParameters** | | struct | **sl::ObjectDetectionSensorsParameters** | | struct | **sl::BodyTrackingSensorsParameters** | | struct | **sl::BodyTrackingSensorsRuntimeParameters**
Structure containing a set of runtime parameters for the body tracking module. | | struct | **sl::PositionalTrackingSensorsParameters** | | struct | **sl::RecordingSensorsParameters** | | struct | **sl::StreamingSensorsParameters** | | struct | **sl::RuntimeSensorsParameters** | | struct | **sl::SensorList**
Structure containing lists of all available sensor devices. | | struct | **sl::StreamingSensorList**
Structure containing lists of all available streaming sensor devices. | | class | **sl::Sensors**
Class for managing multiple sensors (Cameras, Lidars) and fusing their data. | --- # add-on.txt --- # sl_zed ## Files | Name | | -------------- | | **sl_zed/Camera.hpp** | | **sl_zed/CameraOne.hpp** | | **sl_zed/sl_zed/defines.hpp** | --- # mapping ## Files | Name | | -------------- | | **mapping/Mesh.hpp** | --- # sl_fusion ## Files | Name | | -------------- | | **sl_fusion/sl_fusion/defines.hpp** | | **sl_fusion/Fusion.hpp** | --- # sl_sensors ## Files | Name | | -------------- | | **sl_sensors/Sensors.hpp** | --- # sl_core ## Directories | Name | | -------------- | | **mapping** | | **utils** | --- # utils ## Files | Name | | -------------- | | **utils/Core.hpp** | | **utils/types.hpp** | --- # include ## Directories | Name | | -------------- | | **sl_core** | | **sl_fusion** | | **sl_lidar** | | **sl_sensors** | | **sl_zed** | --- # sl_lidar ## Files | Name | | -------------- | | **sl_lidar/Lidar.hpp** | --- # migration-guide-4-0.md --- # release-notes.md --- # sl_fusion/sl_fusion/defines.hpp ## Namespaces | Name | | -------------- | | **sl**
@HideINTERNAL_PUBLICAPI_START | --- # sl_zed/sl_zed/defines.hpp ## Namespaces | Name | | -------------- | | **sl**
@HideINTERNAL_PUBLICAPI_START | ## Classes | | Name | | -------------- | -------------- | | struct | **sl::RecordingStatus**
Structure containing information about the status of the recording. | ## Defines | | Name | | -------------- | -------------- | | | **ZED_SDK_MAJOR_VERSION** | | | **ZED_SDK_MINOR_VERSION** | | | **ZED_SDK_PATCH_VERSION** | | | **ZED_SDK_BUILD_ID** | | | **ZED_SDK_VERSION_ATTRIBUTE** | | | **isValidMeasure**(v) | ## Functions Documentation ### function getZEDSDKRuntimeVersion ```cpp int getZEDSDKRuntimeVersion( int & major, int & minor, int & patch ) ``` Returns the ZED SDK version currently installed on the computer. **Parameters**: * **major** : Major variable to be filled. * **minor** : Minor variable to be filled. * **patch** : Patch variable to be filled. **Return**: * -1 if the ZED SDK was not found * -2 if the ZED SDK version wasn't found * 0 if success ### function getZEDSDKRuntimeVersion_C ```cpp int getZEDSDKRuntimeVersion_C( int & major, int & minor, int & patch ) ``` ### function getZEDSDKBuildVersion ```cpp inline const void getZEDSDKBuildVersion( int & major, int & minor, int & patch ) ``` Returns the ZED SDK version which the current program has been compiled with. **Parameters**: * **major** : Major variable to be filled. * **minor** : Minor variable to be filled. * **patch** : Patch variable to be filled. ## Macros Documentation ### define ZED_SDK_MAJOR_VERSION ```cpp #define ZED_SDK_MAJOR_VERSION 5 ``` ### define ZED_SDK_MINOR_VERSION ```cpp #define ZED_SDK_MINOR_VERSION 3 ``` ### define ZED_SDK_PATCH_VERSION ```cpp #define ZED_SDK_PATCH_VERSION 2 ``` ### define ZED_SDK_BUILD_ID ```cpp #define ZED_SDK_BUILD_ID "localBuild" ``` ### define ZED_SDK_VERSION_ATTRIBUTE ```cpp #define ZED_SDK_VERSION_ATTRIBUTE private: \ uint32_t _zed_sdk_major_version = ZED_SDK_MAJOR_VERSION, _zed_sdk_minor_version = ZED_SDK_MINOR_VERSION, \ _zed_sdk_patch_version = ZED_SDK_PATCH_VERSION; ``` ### define isValidMeasure ```cpp #define isValidMeasure( v ) (std::isfinite(v)) ``` --- # utils/types.hpp ## Namespaces | Name | | -------------- | | **sl**
@HideINTERNAL_PUBLICAPI_START | | **std**
STL namespace. | ## Classes | | Name | | -------------- | -------------- | | class | **sl::String**
Class defining a string. | | struct | **sl::Resolution**
Structure containing the width and height of an image. | | class | **sl::Rect**
Class defining a 2D rectangle with top-left corner coordinates and width/height in pixels. | | struct | **sl::DeviceProperties**
Structure containing information about the properties of a camera. | | struct | **sl::CameraParameters**
Structure containing the intrinsic parameters of a camera. | | struct | **sl::StreamingProperties**
Structure containing information about the properties of a streaming device. | | class | **sl::InputType**
Class defining the input type used in the ZED SDK. | | class | **sl::AI_Model_status**
Structure containing AI model status. | | class | **sl::Matrix3f**
Class representing a generic 3*3 matrix. | | class | **sl::Matrix4f**
Class representing a generic 4*4 matrix. | | class | **sl::Vector2**
Class representing a 2-dimensional vector for both CPU and GPU. | | class | **sl::Vector3**
Class representing a 3-dimensional vector for both CPU and GPU. | | class | **sl::Vector4**
Class representing a 4-dimensional vector for both CPU and GPU. | | struct | **sl::Timestamp**
Structure representing timestamps with utilities. | | struct | **std::hash< sl::String >** | ## Defines | | Name | | -------------- | -------------- | | | **SL_DEPRECATED**(str)
@HideINTERNAL_PUBLICAPI_START | | | **_FCT_CPU_GPU_** | | | **IS_FINITE**(x) | | | **ZEDcudaSafeCall**(err) | | | **TIMING** | | | **INIT_TIMER** | | | **START_TIMER** | | | **DEF_START_TIMER** | | | **STOP_TIMER**(name) | ## Functions Documentation ### function setTimestampClock ```cpp void SL_CORE_EXPORT setTimestampClock( TIMESTAMP_CLOCK clock ) ``` Sets the clock source used for all SDK timestamps (images and sensors). **Parameters**: * **clock** : The desired TIMESTAMP_CLOCK. **Note**: This is a process-wide setting. Call this before opening any camera. ### function getTimestampClock ```cpp TIMESTAMP_CLOCK SL_CORE_EXPORT getTimestampClock() ``` Returns the clock source currently used for SDK timestamps. **Return**: The active TIMESTAMP_CLOCK. ### function getCurrentTimeStamp ```cpp Timestamp SL_CORE_EXPORT getCurrentTimeStamp() ``` Returns the current timestamp using the active clock source (see getTimestampClock). **Return**: A Timestamp representing the current time in nanoseconds. ### function setMaxSystemClockStepMs ```cpp void SL_CORE_EXPORT setMaxSystemClockStepMs( float limit_ms ) ``` Sets the maximum system-clock step (in milliseconds) the SDK will follow per sample when the host clock is adjusted backward (NTP/PTP step, manual date change). **Parameters**: * **limit_ms** : Clamp threshold in milliseconds. * default (setter not called) → **4 ms**: walks to the new offset at 4 ms per IMU sample (~0.8 s of real time to absorb a 1 s step). Safe for slew-only NTP/PTP setups. * any positive value → custom threshold. Higher = follow the host faster, risk briefly decoupling IMU and frame timestamps. Lower = more conservative. * `0.0f` → freeze the offset captured on first use; subsequent host-clock movement is ignored. * any negative value → disable clamping. Raw offset propagates instantly on every call. Use for PTP setups that rely on step corrections landing immediately in reported timestamps. **Note**: Process-wide setting. The environment variable `ZED_SDK_MAX_SYSTEM_CLOCK_STEP_MS`, when set, **always wins** over this setter — an ops-side override for incident debugging. The setter logs a warning the first time it is called while the env var is forcing a different value. Call before opening any camera for the setting to apply from the first sample. Only meaningful in TIMESTAMP_CLOCK::SYSTEM_CLOCK mode — has no effect in TIMESTAMP_CLOCK::MONOTONIC_CLOCK mode where timestamps are monotonic by construction. Forward clock movement always passes through unchanged. Cheat sheet:** | Setup | Recommended value | | -------- | -------- | | Desktop with systemd-timesyncd (slew-only) | default | | PTP with `ptp4l --step_threshold=0` (slew-only) | default | | PTP with step corrections expected | -1.0f | | Deterministic timestamps, ignore the host clock entirely | use TIMESTAMP_CLOCK::MONOTONIC_CLOCK instead | ### function getMaxSystemClockStepMs ```cpp float SL_CORE_EXPORT getMaxSystemClockStepMs() ``` Returns the current system-clock step clamp in milliseconds (see setMaxSystemClockStepMs). ### function __cudaSafeCall ```cpp static inline cudaError __cudaSafeCall( cudaError err, const char * func, const char * file, const int line ) ``` ## Macros Documentation ### define SL_DEPRECATED ```cpp #define SL_DEPRECATED( str ) [[deprecated(str)]] ``` @HideINTERNAL_PUBLICAPI_START @HideINTERNAL_PUBLICAPI_END @HideINTERNAL_PUBLICAPI_START @HideINTERNAL_PUBLICAPI_END ### define _FCT_CPU_GPU_ ```cpp #define _FCT_CPU_GPU_ ``` ### define IS_FINITE ```cpp #define IS_FINITE( x ) std::isfinite(x) ``` ### define ZEDcudaSafeCall ```cpp #define ZEDcudaSafeCall( err ) __cudaSafeCall(err, __CUSTOM__PRETTY__FUNC__, __FILENAME__, __LINE__) ``` ### define TIMING ```cpp #define TIMING ``` ### define INIT_TIMER ```cpp #define INIT_TIMER auto start = std::chrono::high_resolution_clock::now(); ``` ### define START_TIMER ```cpp #define START_TIMER start = std::chrono::high_resolution_clock::now(); ``` ### define DEF_START_TIMER ```cpp #define DEF_START_TIMER auto start = std::chrono::high_resolution_clock::now(); ``` ### define STOP_TIMER ```cpp #define STOP_TIMER( name ) std::cout << name << " " \ << std::chrono::duration_cast(std::chrono::high_resolution_clock::now() - start).count() \ << " ms " << std::endl; ``` --- # std STL namespace.