Core Module

Classes

struct  Timestamp
 Structure representing timestamps with utilities. More...
 
class  String
 Class defining a string. More...
 
struct  Resolution
 Structure containing the width and height of an image. More...
 
class  Rect
 Class defining a 2D rectangle with top-left corner coordinates and width/height in pixels. More...
 
class  Matrix3f
 Class representing a generic 3*3 matrix. More...
 
class  Matrix4f
 Class representing a generic 4*4 matrix. More...
 
class  Vector2< T >
 Class representing a 2-dimensional vector for both CPU and GPU. More...
 
class  Vector3< T >
 Class representing a 3-dimensional vector for both CPU and GPU. More...
 
class  Vector4< T >
 Class representing a 4-dimensional vector for both CPU and GPU. More...
 
class  Mat
 Class representing 1 to 4-channel matrix of float or uchar, stored on CPU and/or GPU side. More...
 
struct  CameraConfiguration
 Structure containing information about the camera sensor. More...
 
struct  CameraInformation
 Structure containing information of a single camera (serial number, model, input type, etc.). More...
 

Enumerations

enum class  UNIT
 Lists available units for measures. More...
 
enum class  COORDINATE_SYSTEM
 Lists available coordinates systems for positional tracking and 3D measures. More...
 
enum class  ERROR_CODE
 Lists error codes in the ZED SDK. More...
 
enum class  MEM
 Lists available memory type. More...
 
enum class  COPY_TYPE
 Lists available copy operation on sl::Mat. More...
 
enum class  MAT_TYPE
 Lists available sl::Mat formats. More...
 
enum class  MODULE
 Lists available modules. More...
 

Functions

int getZEDSDKRuntimeVersion (int &major, int &minor, int &patch)
 Returns the ZED SDK version currently installed on the computer. More...
 
const void getZEDSDKBuildVersion (int &major, int &minor, int &patch)
 Returns the ZED SDK version which the current program has been compiled with. More...
 
String toVerbose (const ERROR_CODE &errorCode)
 Provide a concise sl::ERROR_CODE string. More...
 
void sleep_ms (int time)
 Blocks the execution of the current thread for time milliseconds. More...
 
void sleep_us (int time)
 Blocks the execution of the current thread for time microseconds. More...
 

Enumeration Type Documentation

◆ UNIT

enum UNIT
strong

Lists available units for measures.

Enumerator
MILLIMETER 

International System (1/1000 meters)

CENTIMETER 

International System (1/100 meters)

METER 

International System (1 meter)

INCH 

Imperial Unit (1/12 feet)

FOOT 

Imperial Unit (1 foot)

◆ COORDINATE_SYSTEM

enum COORDINATE_SYSTEM
strong

Lists available coordinates systems for positional tracking and 3D measures.

Enumerator
IMAGE 

Standard coordinates system in computer vision.
Used in OpenCV: see here.

LEFT_HANDED_Y_UP 

Left-handed with Y up and Z forward.
Used in Unity with DirectX.

RIGHT_HANDED_Y_UP 

Right-handed with Y pointing up and Z backward.
Used in OpenGL.

RIGHT_HANDED_Z_UP 

Right-handed with Z pointing up and Y forward.
Used in 3DSMax.

LEFT_HANDED_Z_UP 

Left-handed with Z axis pointing up and X forward.
Used in Unreal Engine.

RIGHT_HANDED_Z_UP_X_FWD 

Right-handed with Z pointing up and X forward.
Used in ROS (REP 103).

◆ ERROR_CODE

enum ERROR_CODE
strong

Lists error codes in the ZED SDK.

Enumerator
SENSORS_DATA_REQUIRED 

The input data does not contains the high frequency sensors data, this is usually because it requires newer SVO/Streaming. In order to work this modules needs inertial data present in it input.

CORRUPTED_FRAME 

The image could be corrupted (enabled with the parameter InitParameters::enable_image_validity_check).

CAMERA_REBOOTING 

The camera is currently rebooting.

SUCCESS 

Standard code for successful behavior.

FAILURE 

Standard code for unsuccessful behavior.

NO_GPU_COMPATIBLE 

No GPU found or CUDA capability of the device is not supported.

NOT_ENOUGH_GPU_MEMORY 

Not enough GPU memory for this depth mode, try a different mode (such as PERFORMANCE), or increase the minimum depth value (see InitParameters::depth_minimum_distance).

CAMERA_NOT_DETECTED 

No camera was detected.

SENSORS_NOT_INITIALIZED 

The MCU that controls the sensors module has an invalid serial number. You can try to recover it by launching the ZED Diagnostic tool from the command line with the option -r.

SENSORS_NOT_AVAILABLE 

A camera with sensor is detected but the sensors (IMU, barometer, ...) cannot be opened. Only the MODEL::ZED does not has sensors. Unplug/replug is required.

INVALID_RESOLUTION 

In case of invalid resolution parameter, such as an upsize beyond the original image size in Camera::retrieveImage.

LOW_USB_BANDWIDTH 

Insufficient bandwidth for the correct use of the camera. This issue can occur when you use multiple cameras or a USB 2.0 port.

CALIBRATION_FILE_NOT_AVAILABLE 

The calibration file of the camera is not found on the host machine. Use ZED Explorer or ZED Calibration to download the factory calibration file.

INVALID_CALIBRATION_FILE 

The calibration file is not valid. Try to download the factory calibration file or recalibrate your camera using ZED Calibration.

INVALID_SVO_FILE 

The provided SVO file is not valid.

SVO_RECORDING_ERROR 

An error occurred while trying to record an SVO (not enough free storage, invalid file, ...).

SVO_UNSUPPORTED_COMPRESSION 

An SVO related error, occurs when NVIDIA based compression cannot be loaded.

END_OF_SVOFILE_REACHED 

SVO end of file has been reached.
No frame will be available until the SVO position is reset.

INVALID_COORDINATE_SYSTEM 

The requested coordinate system is not available.

INVALID_FIRMWARE 

The firmware of the camera is out of date. Update to the latest version.

INVALID_FUNCTION_PARAMETERS 

Invalid parameters have been given for the function.

CUDA_ERROR 

A CUDA error has been detected in the process, in Camera.grab() or Camera.retrieveXXX() only. Activate verbose in Camera.open() for more info.

CAMERA_NOT_INITIALIZED 

The ZED SDK is not initialized. Probably a missing call to Camera.open().

NVIDIA_DRIVER_OUT_OF_DATE 

Your NVIDIA driver is too old and not compatible with your current CUDA version.

INVALID_FUNCTION_CALL 

The call of the function is not valid in the current context. Could be a missing call of Camera.open().

CORRUPTED_SDK_INSTALLATION 

The ZED SDK was not able to load its dependencies or some assets are missing. Reinstall the ZED SDK or check for missing dependencies (cuDNN, TensorRT).

INCOMPATIBLE_SDK_VERSION 

The installed ZED SDK is incompatible with the one used to compile the program.

INVALID_AREA_FILE 

The given area file does not exist. Check the path.

INCOMPATIBLE_AREA_FILE 

The area file does not contain enough data to be used or the DEPTH_MODE used during the creation of the area file is different from the one currently set.

CAMERA_FAILED_TO_SETUP 

Failed to open the camera at the proper resolution. Try another resolution or make sure that the UVC driver is properly installed.

CAMERA_DETECTION_ISSUE 

Your camera can not be opened. Try replugging it to another port or flipping the USB-C connector (if there is one).

CANNOT_START_CAMERA_STREAM 

Cannot start the camera stream. Make sure your camera is not already used by another process or blocked by firewall or antivirus.

NO_GPU_DETECTED 

No GPU found. CUDA is unable to list it. Can be a driver/reboot issue.

PLANE_NOT_FOUND 

Plane not found. Either no plane is detected in the scene, at the location or corresponding to the floor, or the floor plane doesn't match the prior given.

MODULE_NOT_COMPATIBLE_WITH_CAMERA 

The module you try to use is not compatible with your camera MODEL.

Note
MODEL::ZED does not has an IMU and does not support the AI modules.
MOTION_SENSORS_REQUIRED 

The module needs the sensors to be enabled (see InitParameters::sensors_required).

MODULE_NOT_COMPATIBLE_WITH_CUDA_VERSION 

The module needs a newer version of CUDA.

◆ MEM

enum MEM
strong

Lists available memory type.

Enumerator
CPU 

Data will be stored on the CPU (processor side).

GPU 

Data will be stored on the GPU (graphic card side).

◆ COPY_TYPE

enum COPY_TYPE
strong

Lists available copy operation on sl::Mat.

Enumerator
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.

◆ MAT_TYPE

enum MAT_TYPE
strong

Lists available sl::Mat formats.

Note
sl::Mat type depends on image or measure type.
For the dependencies, see sl::VIEW and sl::MEASURE.
Enumerator
F32_C1 

1-channel matrix of float

F32_C2 

2-channel matrix of float

F32_C3 

3-channel matrix of float

F32_C4 

4-channel matrix of float

U8_C1 

1-channel matrix of unsigned char

U8_C2 

2-channel matrix of unsigned char

U8_C3 

3-channel matrix of unsigned char

U8_C4 

4-channel matrix of unsigned char

U16_C1 

1-channel matrix of unsigned short

S8_C4 

4-channel matrix of signed char

◆ MODULE

enum MODULE
strong

Lists available modules.

Enumerator
ALL 

All modules

DEPTH 
POSITIONAL_TRACKING 
OBJECT_DETECTION 
BODY_TRACKING 
SPATIAL_MAPPING 
LAST 

Function Documentation

◆ getZEDSDKRuntimeVersion()

int getZEDSDKRuntimeVersion ( int &  major,
int &  minor,
int &  patch 
)

Returns the ZED SDK version currently installed on the computer.

Parameters
major[out]: Major variable to be filled.
minor[out]: Minor variable to be filled.
patch[out]: Patch variable to be filled.
Returns
-1 if the ZED SDK was not found
-2 if the ZED SDK version wasn't found
0 if success

◆ getZEDSDKBuildVersion()

const void getZEDSDKBuildVersion ( int &  major,
int &  minor,
int &  patch 
)
inline

Returns the ZED SDK version which the current program has been compiled with.

Parameters
major[out]: Major variable to be filled.
minor[out]: Minor variable to be filled.
patch[out]: Patch variable to be filled.

◆ toVerbose()

String sl::toVerbose ( const ERROR_CODE errorCode)

Provide a concise sl::ERROR_CODE string.

Returns
A concise sl::ERROR_CODE string for the user.

◆ sleep_ms()

void sl::sleep_ms ( int  time)
inline

Blocks the execution of the current thread for time milliseconds.

Parameters
time: Number of milliseconds to wait.

◆ sleep_us()

void sl::sleep_us ( int  time)
inline

Blocks the execution of the current thread for time microseconds.

Parameters
time: Number of microseconds to wait.