Core Module

Classes

struct  Timestamp
 Timesamp representation and utilities. More...
 
class  String
 Defines a string. More...
 
struct  Resolution
 Width and height of an array. More...
 
class  Rect
 Defines a 2D rectangle with top-left corner coordinates and width/height in pixels. More...
 
class  Matrix3f
 Represents a generic 3*3 matrix. More...
 
class  Matrix4f
 Represents a generic 4*4 matrix. More...
 
class  Vector2< T >
 Represents a two dimensions vector for both CPU and GPU. More...
 
class  Vector3< T >
 Represents a three dimensions vector for both CPU and GPU. More...
 
class  Vector4< T >
 Represents a four dimensions vector for both CPU and GPU. More...
 
class  Mat
 The Mat class can handle multiple matrix formats from 1 to 4 channels, with different value types (float or uchar), and can be stored 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 unit 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
 List available memory type. More...
 
enum class  COPY_TYPE
 List available copy operation on Mat. More...
 
enum class  MAT_TYPE
 List available Mat formats. More...
 

Functions

int getZEDSDKRuntimeVersion (int &major, int &minor, int &patch)
 Dynamic version verification: Returns the ZED SDK version currently installed on the computer. The major, minor, patch parameters will be filled by reference. More...
 
const void getZEDSDKBuildVersion (int &major, int &minor, int &patch)
 Returns the ZED SDK version which the current program has been compiled with. The major, minor, patch parameters will be filled by reference. More...
 
void sleep_ms (int time)
 Tells the program to wait for x ms. More...
 
void sleep_us (int time)
 Tells the program to wait for x us. More...
 

Enumeration Type Documentation

◆ UNIT

enum UNIT
strong

Lists available unit for measures.

Enumerator
MILLIMETER 

International System, 1/1000 METER.

CENTIMETER 

International System, 1/100 METER.

METER 

International System, 1 METER

INCH 

Imperial Unit, 1/12 FOOT

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 : 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).

◆ ERROR_CODE

enum ERROR_CODE
strong

Lists error codes in the ZED SDK.

Enumerator
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 

The ZED camera is not plugged or detected.

SENSORS_NOT_INITIALIZED 

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

SENSORS_NOT_AVAILABLE 

a ZED-M or ZED2/2i camera is detected but the sensors (imu,barometer...) cannot be opened. Only for ZED-M or ZED2/2i devices. Unplug/replug is required

INVALID_RESOLUTION 

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

LOW_USB_BANDWIDTH 

This issue can occurs when you use multiple ZED or a USB 2.0 port (bandwidth issue).

CALIBRATION_FILE_NOT_AVAILABLE 

ZED calibration file is not found on the host machine. Use ZED Explorer or ZED Calibration to get one.

INVALID_CALIBRATION_FILE 

ZED calibration file is not valid, try to download the factory one or recalibrate your camera using 'ZED Calibration'.

INVALID_SVO_FILE 

The provided SVO file is not valid.

SVO_RECORDING_ERROR 

An recorder related error occurred (not enough free storage, invalid file).

SVO_UNSUPPORTED_COMPRESSION 

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

END_OF_SVOFILE_REACHED 

SVO end of file has been reached, and 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 ZED is out of date. Update to the latest version.

INVALID_FUNCTION_PARAMETERS 

An invalid parameter has been set for the function.

CUDA_ERROR 

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

CAMERA_NOT_INITIALIZED 

In grab() only, ZED SDK is not initialized. Probably a missing call to sl::Camera::open.

NVIDIA_DRIVER_OUT_OF_DATE 

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

INVALID_FUNCTION_CALL 

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

CORRUPTED_SDK_INSTALLATION 

The SDK wasn't able to load its dependencies or somes assets are missing, reinstall the ZED or check for missing dependencies (cudnn, TensorRt).

INCOMPATIBLE_SDK_VERSION 

The installed SDK is incompatible SDK 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 enought data to be used or the sl::DEPTH_MODE used during the creation of the area file is different from the one currently set.

CAMERA_FAILED_TO_SETUP 

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

CAMERA_DETECTION_ISSUE 

Your ZED can not be opened, try replugging it to another USB port or flipping the USB-C connector.

CANNOT_START_CAMERA_STREAM 

Cannot start 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 Object detection module is only compatible with the ZED 2

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

List available memory type.

Enumerator
CPU 

CPU Memory (Processor side).

GPU 

GPU Memory (Graphic card side).

◆ COPY_TYPE

enum COPY_TYPE
strong

List available copy operation on 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

List available Mat formats.

Enumerator
F32_C1 

float 1 channel.

F32_C2 

float 2 channels.

F32_C3 

float 3 channels.

F32_C4 

float 4 channels.

U8_C1 

unsigned char 1 channel.

U8_C2 

unsigned char 2 channels.

U8_C3 

unsigned char 3 channels.

U8_C4 

unsigned char 4 channels.

U16_C1 

unsigned short 1 channel.

S8_C4 

signed char 4 channels.

Function Documentation

◆ getZEDSDKRuntimeVersion()

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

Dynamic version verification: Returns the ZED SDK version currently installed on the computer. The major, minor, patch parameters will be filled by reference.

Returns
-1 if the SDK wasn't found, -2 if the 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. The major, minor, patch parameters will be filled by reference.

// [Windows only]
//using /delayload on the ZED SDK DLLs, this snippet gives you boolean to decide if the SDK should be loaded.
int major_dll, minor_dll, patch_dll;
int major_prg, minor_prg, patch_prg;
bool older_ZED_SDK_available = false;
bool same_ZED_SDK_available = false;
bool newer_ZED_SDK_available = false;
bool ZED_SDK_available = false;
if (getZEDSDKRuntimeVersion(major_dll, minor_dll, patch_dll) == 0) {
getZEDSDKBuildVersion(major_prg, minor_prg, patch_prg);
if (major_dll == major_prg && minor_dll == minor_prg && patch_dll == patch_prg)
same_ZED_SDK_available = true;
if (major_dll > major_prg || (major_dll == major_prg && minor_dll > minor_prg) || (major_dll == major_prg && minor_dll == minor_prg && patch_dll > patch_prg))
newer_ZED_SDK_available = true;
else
older_ZED_SDK_available = true;
if (older_ZED_SDK_available || same_ZED_SDK_available || newer_ZED_SDK_available)
ZED_SDK_available = true;
}
//use ZED_SDK_available or older_ZED_SDK_available or same_ZED_SDK_available or newer_ZED_SDK_available
int getZEDSDKRuntimeVersion(int &major, int &minor, int &patch)
Dynamic version verification: Returns the ZED SDK version currently installed on the computer....
const void getZEDSDKBuildVersion(int &major, int &minor, int &patch)
Returns the ZED SDK version which the current program has been compiled with. The major,...
Definition: defines.hpp:128

◆ sleep_ms()

void sl::sleep_ms ( int  time)
inline

Tells the program to wait for x ms.

Parameters
time: the number of ms to wait.

◆ sleep_us()

void sl::sleep_us ( int  time)
inline

Tells the program to wait for x us.

Parameters
time: the number of us to wait.