Camera Class Reference

This class is the main interface with the camera and the SDK features, such as: video, depth, tracking, mapping and more.
Find more information in the detailed description below. A standard program will use the Camera class like this: More...

Functions

 Camera ()
 Default constructor which creates an empty Camera object.
Parameters will be set when calling open(init_param) with the desired InitParameters . More...
 
 ~Camera ()
 The Camera destructor will call the close() function and clear the memory previously allocated by the object. More...
 
ERROR_CODE open (InitParameters init_parameters=InitParameters())
 Opens the ZED camera from the provided InitParameters.
This function will also check the hardware requirements and run a self-calibration. More...
 
InitParameters getInitParameters ()
 Returns the init parameters used. Correspond to the structure send when the open() function was called. More...
 
bool isOpened ()
 Reports if the camera has been successfully opened. It has the same behavior as checking if open() returns SUCCESS. More...
 
void close ()
 If open() has been called, this function will close the connection to the camera (or the SVO file) and free the corresponding memory. More...
 
ERROR_CODE grab (RuntimeParameters rt_parameters=RuntimeParameters())
 This function will grab the latest images from the camera, rectify them, and compute the measurements based on the RuntimeParameters provided (depth, point cloud, tracking, etc.)
As measures are created in this function, its execution can last a few milliseconds, depending on your parameters and your hardware.
The exact duration will mostly depend on the following parameters: More...
 
RuntimeParameters getRuntimeParameters ()
 Returns the runtime parameters used. Correspond to the structure send when the grab() function was called. More...
 
CameraInformation getCameraInformation (Resolution image_size=Resolution(0, 0))
 Returns the calibration parameters, serial number and other information about the camera being used. More...
 
void updateSelfCalibration ()
 Perform a new self calibration process. More...
 
CUcontext getCUDAContext ()
 Gets the Camera-created CUDA context for sharing it with other CUDA-capable libraries. This can be useful for sharing GPU memories. If you're looking for the opposite mechanism, where an existing CUDA context is given to the Camera, please check InitParameters::sdk_cuda_ctx. More...
 
CUstream getCUDAStream ()
 
ERROR_CODE findPlaneAtHit (sl::uint2 coord, sl::Plane &plane)
 Checks the plane at the given left image coordinates. More...
 
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. More...
 
ERROR_CODE getCurrentMinMaxDepth (float &min, float &max)
 Gets the current range of perceived depth. More...
 
 Camera (const Camera &)=delete
 The Camera object cannot be copied. Therfore, its copy constructor is disabled. If you need to share a Camera instance across several threads or object, please consider using a pointer. More...
 
Video
ERROR_CODE retrieveImage (Mat &mat, VIEW view=VIEW::LEFT, MEM type=MEM::CPU, Resolution image_size=Resolution(0, 0))
 Retrieves images from the camera (or SVO file). More...
 
int getCameraSettings (VIDEO_SETTINGS settings)
 Returns the current value of the requested camera setting. (gain, brightness, hue, exposure, etc.) More...
 
ERROR_CODE getCameraSettings (VIDEO_SETTINGS settings, Rect &roi, sl::SIDE side=sl::SIDE::BOTH)
 Overloaded function for VIDEO_SETTINGS::AEC_AGC_ROI which takes a Rect as parameter. More...
 
void setCameraSettings (VIDEO_SETTINGS settings, int value=VIDEO_SETTINGS_VALUE_AUTO)
 Sets the value of the requested camera setting. (gain, brightness, hue, exposure, etc.) More...
 
ERROR_CODE setCameraSettings (VIDEO_SETTINGS settings, Rect roi, sl::SIDE side=sl::SIDE::BOTH, bool reset=false)
 Overloaded function for VIDEO_SETTINGS::AEC_AGC_ROI which takes a Rect as parameter. More...
 
float getCurrentFPS ()
 Returns the current framerate at which the grab() method is successfully called. The returned value is based on the difference of camera timestamps between two successful grab() calls. More...
 
Timestamp getTimestamp (sl::TIME_REFERENCE reference_time)
 Returns the timestamp in the requested TIME_REFERENCE. More...
 
unsigned int getFrameDroppedCount ()
 Returns the number of frames dropped since grab() was called for the first time. More...
 
int getSVOPosition ()
 Returns the current playback position in the SVO file. More...
 
void setSVOPosition (int frame_number)
 Sets the playback cursor to the desired frame number in the SVO file. More...
 
int getSVONumberOfFrames ()
 Returns the number of frames in the SVO file. More...
 
Depth Sensing
ERROR_CODE retrieveMeasure (Mat &mat, MEASURE measure=MEASURE::DEPTH, MEM type=MEM::CPU, Resolution image_size=Resolution(0, 0))
 Computed measures, like depth, point cloud, or normals, can be retrieved using this method. More...
 
ERROR_CODE setRegionOfInterest (sl::Mat &roi_mask)
 Defines a region of interest to focus on for all the SDK, discarding other parts. More...
 
Positional Tracking
ERROR_CODE enablePositionalTracking (PositionalTrackingParameters tracking_parameters=PositionalTrackingParameters())
 Initializes and starts the positional tracking processes. More...
 
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. More...
 
ERROR_CODE saveAreaMap (String area_file_path)
 Saves the current area learning file. The file will contain spatial memory data generated by the tracking. More...
 
AREA_EXPORTING_STATE getAreaExportState ()
 Returns the state of the spatial memory export process. More...
 
ERROR_CODE resetPositionalTracking (const Transform &path)
 Resets the tracking, and re-initializes the position with the given transformation matrix. More...
 
void disablePositionalTracking (String area_file_path="")
 Disables the positional tracking. More...
 
bool isPositionalTrackingEnabled ()
 Tells if the tracking module is enabled. More...
 
PositionalTrackingParameters getPositionalTrackingParameters ()
 Returns the positional tracking parameters used. Correspond to the structure send when the enablePositionalTracking() function was called. More...
 
ERROR_CODE getSensorsData (SensorsData &data, TIME_REFERENCE reference_time)
 Retrieves the Sensors (IMU,magnetometer,barometer) Data at a specific time reference. More...
 
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(). More...
 
Spatial Mapping
ERROR_CODE enableSpatialMapping (SpatialMappingParameters spatial_mapping_parameters=SpatialMappingParameters())
 Initializes and starts the spatial mapping processes. More...
 
SPATIAL_MAPPING_STATE getSpatialMappingState ()
 Returns the current spatial mapping state. More...
 
void requestSpatialMapAsync ()
 Starts the spatial map generation process in a non blocking thread from the spatial mapping process. More...
 
ERROR_CODE getSpatialMapRequestStatusAsync ()
 Returns the spatial map generation status. This status allows to know if the mesh can be retrieved by calling retrieveSpatialMapAsync. More...
 
ERROR_CODE retrieveSpatialMapAsync (Mesh &mesh)
 Retrieves the current generated spatial map only if SpatialMappingParameters::map_type was set as SPATIAL_MAP_TYPE::MESH. More...
 
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. The fused point cloud will only be available when getMeshRequestStatusAsync() returns SUCCESS. More...
 
ERROR_CODE extractWholeSpatialMap (Mesh &mesh)
 Extracts the current spatial map from the spatial mapping process only if SpatialMappingParameters::map_type was set as SPATIAL_MAP_TYPE::MESH. More...
 
ERROR_CODE extractWholeSpatialMap (FusedPointCloud &fpc)
 Extracts the current spatial map from the spatial mapping process only if SpatialMappingParameters::map_type was set as SPATIAL_MAP_TYPE::FUSED_POINT_CLOUD. More...
 
void pauseSpatialMapping (bool status)
 Pauses or resumes the spatial mapping processes. More...
 
void disableSpatialMapping ()
 Disables the spatial mapping process. More...
 
SpatialMappingParameters getSpatialMappingParameters ()
 Returns the spatial mapping parameters used. Correspond to the structure send when the enableSpatialMapping() function was called. More...
 
Recording
ERROR_CODE enableRecording (RecordingParameters recording_parameters)
 Creates an SVO file to be filled by record(). More...
 
RecordingStatus getRecordingStatus ()
 Get the recording information. More...
 
void pauseRecording (bool status)
 Pauses or resumes the recording. More...
 
void disableRecording ()
 Disables the recording initiated by enableRecording() and closes the generated file. More...
 
RecordingParameters getRecordingParameters ()
 Returns the recording parameters used. Correspond to the structure send when the enableRecording() function was called. More...
 
Streaming
ERROR_CODE enableStreaming (StreamingParameters streaming_parameters=StreamingParameters())
 Creates a streaming pipeline. More...
 
void disableStreaming ()
 Disables the streaming initiated by enableStreaming() More...
 
bool isStreamingEnabled ()
 Tells if the streaming is running (true) or still initializing (false) More...
 
StreamingParameters getStreamingParameters ()
 Returns the streaming parameters used. Correspond to the structure send when the enableStreaming() function was called. More...
 
Object Detection
ERROR_CODE enableObjectDetection (ObjectDetectionParameters object_detection_parameters=ObjectDetectionParameters())
 Initializes and starts the Deep Learning detection module.
The object detection module currently supports two types of detection : More...
 
void pauseObjectDetection (bool status)
 Pauses or resumes the object detection processes. More...
 
void disableObjectDetection ()
 Disables the Object Detection process. More...
 
ERROR_CODE ingestCustomBoxObjects (std::vector< CustomBoxObjectData > &objects_in)
 Feed the 3D Object tracking function with your own 2D bounding boxes from your own detection algorithm. More...
 
ERROR_CODE retrieveObjects (Objects &objects, ObjectDetectionRuntimeParameters parameters=ObjectDetectionRuntimeParameters())
 Retrieve objects detected by the object detection module. More...
 
ERROR_CODE getObjectsBatch (std::vector< sl::ObjectsBatch > &trajectories)
 Get a batch of detected objects. More...
 
bool isObjectDetectionEnabled ()
 Tells if the object detection module is enabled. More...
 
ObjectDetectionParameters getObjectDetectionParameters ()
 Returns the object detection parameters used. Correspond to the structure send when the enableObjectDetection() function was called. More...
 

Static Functions

static String getSDKVersion ()
 Returns the version of the currently installed ZED SDK. More...
 
static void getSDKVersion (int &major, int &minor, int &patch)
 Returns the version of the currently installed ZED SDK. More...
 
static std::vector< sl::DevicePropertiesgetDeviceList ()
 List all the connected devices with their associated information. More...
 
static std::vector< sl::StreamingPropertiesgetStreamingDeviceList ()
 List all the streaming devices with their associated information. More...
 
static sl::ERROR_CODE reboot (int sn, bool fullReboot=true)
 Performs an hardware reset of the ZED 2 and the ZED2i. More...
 
static AI_Model_status checkAIModelStatus (AI_MODELS model, int gpu_id=0)
 Check if a corresponding optimized engine is found for the requested Model based on your rig configuration. More...
 
static ERROR_CODE optimizeAIModel (sl::AI_MODELS model, int gpu_id=0)
 Optimize the requested model, possible download if the model is not present on the host. More...
 

Detailed Description

This class is the main interface with the camera and the SDK features, such as: video, depth, tracking, mapping and more.
Find more information in the detailed description below. A standard program will use the Camera class like this:

#include <sl/Camera.hpp>
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
// Open the camera
ERROR_CODE err = zed.open(init_params);
if (err != SUCCESS) {
std::cout << err << " exit program " << std::endl;
return -1;
}
// --- Main loop grabing images and depth values
// Capture 50 frames and stop
int i = 0;
Mat image, depth;
while (i < 50) {
// Grab an image
if (zed.grab() == 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<sl::uchar4>(image.getWidth() / 2, image.getHeight() / 2, &centerBGRA);
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<float>(depth.getWidth() / 2, depth.getHeight() / 2, &centerDepth);
std::cout << "Image " << i << " center depth:" << centerDepth << std::endl;
i++;
}
}
// --- Close the Camera
zed.close();
return 0;
}
Camera()
Default constructor which creates an empty Camera object. Parameters will be set when calling open(...
Represents a four dimensions vector for both CPU and GPU.
Definition: types.hpp:1557
ERROR_CODE
Lists error codes in the ZED SDK.
Definition: types.hpp:368
Definition: defines.hpp:135

Constructor and Destructor

◆ Camera() [1/2]

Camera ( )

Default constructor which creates an empty Camera object.
Parameters will be set when calling open(init_param) with the desired InitParameters .

The Camera object can be created like this:

Camera zed;

or

Camera* zed = new Camera();

◆ ~Camera()

~Camera ( )

The Camera destructor will call the close() function and clear the memory previously allocated by the object.

◆ Camera() [2/2]

Camera ( const Camera )
delete

The Camera object cannot be copied. Therfore, its copy constructor is disabled. If you need to share a Camera instance across several threads or object, please consider using a pointer.

See also
Camera()

Functions

◆ open()

ERROR_CODE open ( InitParameters  init_parameters = InitParameters())

Opens the ZED camera from the provided InitParameters.
This function will also check the hardware requirements and run a self-calibration.

Parameters
init_parameters: a structure containing all the initial parameters. default : a preset of InitParameters.
Returns
An error code giving information about the internal process. If 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:

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 != SUCCESS) {
std::cout << toString(err) << std::endl; // Display the error
exit(-1);
}
* toString(const FLIP_MODE &flip_mode)
Note
If you are having issues opening a camera, the diagnostic tool provided in the SDK can help you identify to problems.
If this function is called on an already opened camera, close() will be called.
Windows: C:\Program Files (x86)\ZED SDK\tools\ZED Diagnostic.exe
Linux: /usr/local/zed/tools/ZED Diagnostic

◆ getInitParameters()

InitParameters getInitParameters ( )

Returns the init parameters used. Correspond to the structure send when the open() function was called.

Returns
InitParameters containing the parameters used to initialize the Camera object.

◆ isOpened()

bool isOpened ( )
inline

Reports if the camera has been successfully opened. It has the same behavior as checking if open() returns SUCCESS.

Returns
true if the ZED is already setup, otherwise false.

◆ close()

void close ( )

If open() has been called, this function will close the connection to the camera (or the SVO file) and free the corresponding memory.

If open() wasn't called or failed, this function won't have any effects.

Note
If an asynchronous task is running within the Camera object, like saveAreaMap(), this function 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 function will destroy it.
Therefore you need to make sure to delete your GPU sl::Mat objects before the context is destroyed.

◆ grab()

ERROR_CODE grab ( RuntimeParameters  rt_parameters = RuntimeParameters())

This function will grab the latest images from the camera, rectify them, and compute the measurements based on the RuntimeParameters provided (depth, point cloud, tracking, etc.)
As measures are created in this function, its execution can last a few milliseconds, depending on your parameters and your hardware.
The exact duration will mostly depend on the following parameters:


This function is meant to be called frequently in the main loop of your application.

Note
Since ZED SDK 3.0, this function 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 .
Parameters
rt_parameters: a structure containing all the runtime parameters. default : a preset of RuntimeParameters.
Returns
Returning SUCCESS means that no problem was encountered. Returned errors can be displayed using toString(error)
// Set runtime parameters after opening the camera
RuntimeParameters runtime_param;
runtime_param.sensing_mode = SENSING_MODE::STANDARD; // Use STANDARD sensing mode
Mat image;
while (true) {
// Grab an image
if (zed.grab(runtime_param) == 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
}
}

◆ getRuntimeParameters()

RuntimeParameters getRuntimeParameters ( )

Returns the runtime parameters used. Correspond to the structure send when the grab() function was called.

Returns
RuntimeParameters containing the parameters that defines the behavior of the grab.

◆ getCameraInformation()

CameraInformation getCameraInformation ( Resolution  image_size = Resolution(0, 0))

Returns the calibration parameters, serial number and other information about the camera being used.

As calibration parameters depend on the image resolution, you can provide a custom resolution as a parameter to get scaled information.
When reading an SVO file, the parameters will correspond to the camera used for recording.

Parameters
image_size: You can specify a size different from default image size to get the scaled camera information. default = (0,0) meaning original image size (given by .camera_configuration.resolution ).
Returns
CameraInformation containing the calibration parameters of the ZED, as well as serial number and firmware version.
Note
The CameraInformation will contain two types of calibration parameters:
  • camera_configuration::calibration_parameters : it contains the calibration (single camera matrix, single distortion matrix, rotation/translation matrix between both eyes) 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, wich 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 returned camera_configuration::calibration_parameters might vary between two execution due to the self-calibration being ran in the open() method.
The calibration file SNXXXX.conf can be found in:
  • C:/ProgramData/Stereolabs/settings/ (Windows)
  • /usr/local/zed/settings/ (Linux)

◆ updateSelfCalibration()

void updateSelfCalibration ( )

Perform a new self calibration process.

In some cases, due to temperature changes or strong vibrations, the stereo calibration becomes less accurate. Use this function to update the self-calibration data and get more reliable depth values.

Note
The self calibration will occur at the next grab() call.
This function 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.

◆ getCUDAContext()

CUcontext getCUDAContext ( )

Gets the Camera-created CUDA context for sharing it with other CUDA-capable libraries. This can be useful for sharing GPU memories. If you're looking for the opposite mechanism, where an existing CUDA context is given to the Camera, please check InitParameters::sdk_cuda_ctx.

Returns
The CUDA context used for GPU calls.

◆ getCUDAStream()

CUstream getCUDAStream ( )

◆ retrieveImage()

ERROR_CODE retrieveImage ( Mat mat,
VIEW  view = VIEW::LEFT,
MEM  type = MEM::CPU,
Resolution  image_size = Resolution(0, 0) 
)

Retrieves images from the camera (or SVO file).

Multiple images are available along with a view of various measures for display purposes.
Available images and views are listed here.
As an example, VIEW::DEPTH can be used to get a gray-scale version of the depth map, but the actual depth values can be retrieved using 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 .camera_configuration.resolution.
However, you can request custom resolutions. For example, requesting a smaller image can help you speed up your application.

Warning
A sl::Mat resolution higher than the camera resolution cannot be requested.
Parameters
mat: the Mat to store the image. The function 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: whether the image should be provided in CPU or GPU memory. default : MEM::CPU.
image_size: if specified, define the resolution of the output mat. If set to Resolution(0,0) , the ZED resolution will be taken. default : (0,0).
Returns
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 width/height is higher than the input resolution (width,height) or the side by side input resolution (width x 2,height) for side by side view mode, ERROR_CODE::FAILURE if another error occurred.
Note
As this function retrieves the images grabbed by the grab() function, it should be called afterward.
Mat leftImage; //create sl::Mat objects to store the image
while (true) {
// Grab an image
if (zed.grab() == 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<sl::uchar4>(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;
}
}

◆ getCameraSettings() [1/2]

int getCameraSettings ( VIDEO_SETTINGS  settings)

Returns the current value of the requested camera setting. (gain, brightness, hue, exposure, etc.)

Possible values (range) of each setting are available here.

Parameters
setting: the requested setting.
Returns
The current value for the corresponding setting. Returns -1 if encounters an error.
int gain = zed.getCameraSettings(VIDEO_SETTINGS::GAIN);
std::cout << "Current gain value: " << gain << std::endl;
Note
Works only if the camera is open in LIVE or STREAM mode. (Settings aren't exported in the SVO file format)

◆ getCameraSettings() [2/2]

ERROR_CODE getCameraSettings ( VIDEO_SETTINGS  settings,
Rect roi,
sl::SIDE  side = sl::SIDE::BOTH 
)

Overloaded function for VIDEO_SETTINGS::AEC_AGC_ROI which takes a Rect as parameter.

Parameters
setting: must be set at VIDEO_SETTINGS::AEC_AGC_ROI, otherwise the function will have no impact.
roi: Rect that defines the current target applied for AEC/AGC.
Returns
ERROR_CODE::SUCCESS if ROI has been applied. Other ERROR_CODE otherwise.
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.

◆ setCameraSettings() [1/2]

void setCameraSettings ( VIDEO_SETTINGS  settings,
int  value = VIDEO_SETTINGS_VALUE_AUTO 
)

Sets the value of the requested camera setting. (gain, brightness, hue, exposure, etc.)

Possible values (range) of each setting are available here.

Parameters
settings: the setting to be set.
value: the value to set, default : auto mode
//Set the gain to 50
zed.setCameraSettings(VIDEO_SETTINGS::GAIN, 50);
Warning
Setting VIDEO_SETTINGS::EXPOSURE or VIDEO_SETTINGS::GAIN to default will automatically sets the other to default.
Note
Works only if the camera is open in LIVE or STREAM mode.

◆ setCameraSettings() [2/2]

ERROR_CODE setCameraSettings ( VIDEO_SETTINGS  settings,
Rect  roi,
sl::SIDE  side = sl::SIDE::BOTH,
bool  reset = false 
)

Overloaded function for VIDEO_SETTINGS::AEC_AGC_ROI which takes a Rect as parameter.

Parameters
setting: must be set at VIDEO_SETTINGS::AEC_AGC_ROI, otherwise the function will have no impact.
roi: Rect that defines the target to be applied for AEC/AGC computation. Must be given according to camera resolution.
Returns
ERROR_CODE::SUCCESS if ROI has been applied. Other ERROR_CODE otherwise.
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.

◆ getCurrentFPS()

float getCurrentFPS ( )

Returns the current framerate at which the grab() method is successfully called. The returned value is based on the difference of camera timestamps between two successful grab() calls.

Returns
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.
int current_fps = zed.getCurrentFPS();
std::cout << "Current framerate: " << current_fps << std::endl;

◆ getTimestamp()

Timestamp getTimestamp ( sl::TIME_REFERENCE  reference_time)

Returns the timestamp in the requested TIME_REFERENCE.

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

Parameters
reference_time: The selected TIME_REFERENCE.
Returns
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.
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;

◆ getFrameDroppedCount()

unsigned int getFrameDroppedCount ( )

Returns the number of frames dropped since grab() was called for the first time.

A dropped frame corresponds to a frame that never made it to the grab function.
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).

Returns
The number of frames dropped since the first grab() call.

◆ getSVOPosition()

int getSVOPosition ( )

Returns the current playback position in the SVO file.

The position corresponds to the number of frames already read from the SVO file, starting from 0 to n.
Each grab() call increases this value by one (except when using InitParameters::svo_real_time_mode).

Returns
The current frame position in the SVO file. Returns -1 if the SDK is not reading an SVO.
Note
Works only if the camera is open in SVO playback mode.
See also
setSVOPosition() for an example.

◆ setSVOPosition()

void setSVOPosition ( int  frame_number)

Sets the playback cursor to the desired frame number in the SVO file.

This function allows you to move around within a played-back SVO file. After calling, the next call to grab() will read the provided frame number.

Parameters
frame_number: the number of the desired frame to be decoded.
Note
Works only if the camera is open in SVO playback mode.
#include <sl/Camera.hpp>
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 != SUCCESS) {
std::cout << toString(err) << std::endl;
exit(-1);
}
// Loop between frame 0 and 50
int i = 0;
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() == SUCCESS) {
zed.retrieveImage(leftImage, VIEW::LEFT); // Get the rectified left image
// Use the image in your application
}
}
// Close the Camera
zed.close();
return 0;
}

◆ getSVONumberOfFrames()

int getSVONumberOfFrames ( )

Returns the number of frames in the SVO file.

Returns
The total number of frames in the SVO file (-1 if the SDK is not reading a SVO).
Note
Works only if the camera is open in SVO reading mode.
See also
setSVOPosition() for an example.

◆ retrieveMeasure()

ERROR_CODE retrieveMeasure ( Mat mat,
MEASURE  measure = MEASURE::DEPTH,
MEM  type = MEM::CPU,
Resolution  image_size = Resolution(0, 0) 
)

Computed measures, like depth, point cloud, or normals, can be retrieved using this method.


Multiple measures are available after a grab() call. A full list is available here.

Memory
By default, images are copied from GPU memory to CPU memory (RAM) when this function is called.
If your application can use GPU images, using the type parameter can increase performance by avoiding this copy.
If the provided Mat object is already allocated and matches the requested image format, memory won't be re-allocated.

Measure size
By default, measures are returned in the resolution provided by .camera_configuration.resolution .
However, custom resolutions can be requested. For example, requesting a smaller measure can help you speed up your application.

Warning
A sl::Mat resolution higher than the camera resolution cannot be requested.
Parameters
mat: the Mat to store the measure. The function 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: the type of the memory of provided mat that should by used. default : MEM::CPU.
image_size: if specified, define the resolution of the output mat. If set to Resolution(0,0) , the ZED resolution will be taken. default : (0,0).
Returns
"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 width/height is higher than camera.getCameraInformation().camera_configuration.resolution or camera.getCameraInformation().camera_configuration.resolution x 2 for side by side view mode, 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 SUCCESS.

Measures containing "RIGHT" in their names, requires InitParameters::enable_right_side_measure to be enabled.
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() == 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<float>(x, y, &centerDepth, MEM::CPU); // each depth map pixel is a float value
if (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<sl::float4>(x, y, &pcValue); // each point cloud pixel contains 4 floats, so we are using a sl::float4
if (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;
}
}
}
Width and height of an array.
Definition: types.hpp:188
size_t height
Definition: types.hpp:190
size_t width
Definition: types.hpp:189

◆ setRegionOfInterest()

ERROR_CODE setRegionOfInterest ( sl::Mat roi_mask)

Defines a region of interest to focus on for all the SDK, discarding other parts.

Parameters
roi_maskthe Mat defining the requested region of interest, all pixel set to 0 will be discard. If empty, set all pixels as valid, otherwise should fit the resolution of the current instance and its type should be U8_C1.
Returns
An ERROR_CODE if something went wrong.

◆ enablePositionalTracking()

ERROR_CODE enablePositionalTracking ( PositionalTrackingParameters  tracking_parameters = PositionalTrackingParameters())

Initializes and starts the positional tracking processes.

This function 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 function.

Parameters
tracking_parameters: A structure containing all the PositionalTrackingParameters . default : a preset of PositionalTrackingParameters.
Returns
ERROR_CODE::FAILURE if the area_file_path file wasn't found, 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.
#include <sl/Camera.hpp>
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 != 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 != SUCCESS) {
std::cout << "Tracking error: " << toString(err) << std::endl;
exit(-1);
}
// --- Main loop
while (true) {
if (zed.grab() == 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;
}

◆ getPosition()

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.


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

Parameters
camera_pose[out]: 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.
Returns
The current state of the tracking process.


Extract Rotation Matrix : camera_pose.getRotation();
Extract Translation Vector: camera_pose.getTranslation();
Convert to Orientation / quaternion : camera_pose.getOrientation();

Note
The position is provided in the InitParameters::coordinate_system . See COORDINATE_SYSTEM for its physical origin.
Warning
This function requires the tracking to be enabled. enablePositionalTracking() .
// --- Main loop
while (true) {
if (zed.grab() == 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;
}
}

◆ saveAreaMap()

ERROR_CODE saveAreaMap ( String  area_file_path)

Saves the current area learning file. The file will contain spatial memory data generated by the tracking.

If the tracking has been initialized with PositionalTrackingParameters::enable_area_memory to true (default), the function 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 function is asynchronous, and only triggers the file generation. You can use getAreaExportState() to get the export state. The positional tracking keeps running while exporting.

Parameters
area_file_path: save the spatial memory database in an '.area' file.
Returns
ERROR_CODE::FAILURE if the area_file_path file wasn't found, SUCCESS otherwise.
See also
getAreaExportState()
Note
This function is asynchronous because the generated data can be heavy, be sure to loop over the getAreaExportState() function 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() function 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.
// --- 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");
while (export_state == sl::AREA_EXPORTING_STATE::RUNNING) {
export_state = zed.getAreaExportState();
}
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;
void sleep_ms(int time)
Tells the program to wait for x ms.
Definition: types.hpp:779

◆ getAreaExportState()

AREA_EXPORTING_STATE getAreaExportState ( )

Returns the state of the spatial memory export process.

As saveAreaMap() only starts the exportation, this function allows you to know when the exportation finished or if it failed.

Returns
The current state of the spatial memory export process

◆ resetPositionalTracking()

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 function is called. By default, it is set to identity.
Returns
ERROR_CODE::SUCCESS if the tracking has been reset, ERROR_CODE::FAILURE otherwise.
Note
Please note that this function will also flush the accumulated or loaded spatial memory.

◆ disablePositionalTracking()

void disablePositionalTracking ( String  area_file_path = "")

Disables the positional tracking.

The positional tracking is immediately stopped. If a file path is given, saveAreaMap(area_file_path) will be called asynchronously. See getAreaExportState() to get the exportation state.
If the tracking has been enabled, this function will automatically be called by close() .

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 map SENSING_MODE chosen during the recording. The same mode must be used to reload the database.

◆ isPositionalTrackingEnabled()

bool isPositionalTrackingEnabled ( )

Tells if the tracking module is enabled.

◆ getPositionalTrackingParameters()

PositionalTrackingParameters getPositionalTrackingParameters ( )

Returns the positional tracking parameters used. Correspond to the structure send when the enablePositionalTracking() function was called.

Returns
PositionalTrackingParameters containing the parameters used for positional tracking initialization.

◆ getSensorsData()

ERROR_CODE getSensorsData ( SensorsData data,
TIME_REFERENCE  reference_time 
)

Retrieves the Sensors (IMU,magnetometer,barometer) Data at a specific time reference.

Calling getSensosrData with TIME_REFERENCE::CURRENT gives you the latest sensors data received. Getting all the data requires to call this function 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 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 gyroscope and accelerometer are synchronized. The delta time between previous and current value can be calculated using data.imu.timestamp.

Note
The IMU quaternion (fused data) is given in the specified COORDINATE_SYSTEM of InitParameters.
Returns
ERROR_CODE::SUCCESS if sensors data have been extracted.
ERROR_CODE::SENSORS_NOT_AVAILABLE if the camera model is a 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.
Warning
In SVO or STREAM mode, the TIME_REFERENCE::CURRENT is currently not available (yielding ERROR_CODE::INVALID_FUNCTION_PARAMETERS. Only the quaternion data and barometer data (if available) at TIME_REFERENCE::IMAGE are available. Other values will be set to 0.
if (zed.getSensorsData(sensors_data, TIME_REFERENCE::CURRENT) == ERROR_CODE::SUCCESS) {
cout << " - IMU:\n";
cout << " \t Orientation: {" << sensors_data.imu.pose.getOrientation() << "}\n";
cout << " \t Acceleration: {" << sensors_data.imu.linear_acceleration << "} [m/sec^2]\n";
cout << " \t Angular Velocitiy: {" << sensors_data.imu.angular_velocity << "} [deg/sec]\n";
cout << " - Magnetometer\n \t Magnetic Field: {" << sensors_data.magnetometer.magnetic_field_calibrated << "} [uT]\n";
cout << " - Barometer\n \t Atmospheric pressure:" << sensors_data.barometer.pressure << " [hPa]\n";
// retrieves camera sensors temperature
cout << " - Temperature\n";
float temperature;
for (int s = 0; s < static_cast<int>(SensorsData::TemperatureData::SENSOR_LOCATION::LAST); s++) {
auto sensor_loc = static_cast<SensorsData::TemperatureData::SENSOR_LOCATION>(s);
// depending on your Camera model or its firmware, differents sensors can give thermal information
if (sensors_data.temperature.get(sensor_loc, temperature) == ERROR_CODE::SUCCESS)
cout << " \t " << sensor_loc << ": " << temperature << "C\n";
}
}
SENSOR_LOCATION
Defines the location of each sensor for TemperatureData.
Definition: Core.hpp:1347

◆ setIMUPrior()

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

This function can be used to assist the positional tracking rotation while using a ZED Mini or a ZED 2.

Note
This function is only effective if a ZED-M or a ZED 2 is used.
It needs to be called before the grab() function.
Parameters
sl::Transformto be ingested into IMU fusion. Note that only the rotation is used.
Returns
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).

◆ enableSpatialMapping()

ERROR_CODE enableSpatialMapping ( SpatialMappingParameters  spatial_mapping_parameters = SpatialMappingParameters())

Initializes and starts the spatial mapping processes.

The spatial mapping will create a geometric representation of the scene based on both tracking data and 3D point clouds.
The resulting output can be a Mesh or a FusedPointCloud. It can be be obtained by calling extractWholeSpatialMap() or retrieveSpatialMapAsync(). Note that retrieveSpatialMapAsync() should be called after requestSpatialMapAsync().

Parameters
spatial_mapping_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.
Returns
SUCCESS if everything went fine, ERROR_CODE::FAILURE otherwise.
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.
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.
#ifndef NDEBUG
#error "Spatial mapping requires Release mode, not Debug."
#endif
#include <sl/Camera.hpp>
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 != SUCCESS)
exit(-1);
// Positional tracking needs to be enabled before using spatial mapping
sl::PositionalTrackingParameters tracking_parameters;
err = zed.enablePositionalTracking(tracking_parameters);
if (err != SUCCESS)
exit(-1);
// Enable spatial mapping
sl::SpatialMappingParameters mapping_parameters;
err = zed.enableSpatialMapping(mapping_parameters);
if (err != 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() == SUCCESS) {
// In the background, 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: " << spatialMappingState2str(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.extractWholeMesh(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;
}
A mesh contains the geometric (and optionally texture) data of the scene captured by spatial mapping.
Definition: Mesh.hpp:291
bool save(String filename, MESH_FILE_FORMAT type=MESH_FILE_FORMAT::OBJ, chunkList IDs=chunkList())
Saves the current Mesh into a file.
bool filter(MeshFilterParameters mesh_filter_params=MeshFilterParameters(), bool update_chunk_only=false)
Filters the mesh.
SPATIAL_MAPPING_STATE
Gives the spatial mapping state.
Definition: defines.hpp:462
Parameters for positional tracking initialization.
Definition: Camera.hpp:559
Sets the spatial mapping parameters.
Definition: Camera.hpp:688

◆ getSpatialMappingState()

SPATIAL_MAPPING_STATE getSpatialMappingState ( )

Returns the current spatial mapping state.

As the spatial mapping runs asynchronously, this function allows you to get reported errors or status info.

Returns
The current state of the spatial mapping process
See also
SPATIAL_MAPPING_STATE

◆ requestSpatialMapAsync()

void requestSpatialMapAsync ( )

Starts the spatial map generation process in a non blocking thread from the spatial mapping process.

The spatial map generation can take a long time depending on the mapping resolution and covered area. This function will trigger the generation of a mesh without blocking the program. You can get info about the current generation using getSpatialMapRequestStatusAsync(), and retrieve the mesh using retrieveSpatialMapAsync(...) .

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.
zed.requestSpatialMapAsync();
while (zed.getSpatialMapRequestStatusAsync() == ERROR_CODE::FAILURE) {
//Mesh is still generating
}
if (zed.getSpatialMapRequestStatusAsync() == SUCCESS) {
zed.retrieveSpatialMapAsync(mesh);
std::cout << "Number of triangles in the mesh: " << mesh.getNumberOfTriangles() << std::endl;
}

◆ getSpatialMapRequestStatusAsync()

ERROR_CODE getSpatialMapRequestStatusAsync ( )

Returns the spatial map generation status. This status allows to know if the mesh can be retrieved by calling retrieveSpatialMapAsync.

Returns
SUCCESS if the mesh is ready and not yet retrieved, otherwise ERROR_CODE::FAILURE.


See requestSpatialMapAsync() for an example.

◆ retrieveSpatialMapAsync() [1/2]

ERROR_CODE retrieveSpatialMapAsync ( Mesh mesh)

Retrieves the current generated spatial map only if SpatialMappingParameters::map_type was set as SPATIAL_MAP_TYPE::MESH.

After calling requestSpatialMapAsync , this function allows you to retrieve the generated mesh. The mesh will only be available when getMeshRequestStatusAsync() returns SUCCESS

Parameters
mesh: [out] The mesh to be filled with the generated spatial map.
Returns
SUCCESS if the mesh is retrieved, otherwise 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.

◆ retrieveSpatialMapAsync() [2/2]

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. The fused point cloud will only be available when getMeshRequestStatusAsync() returns SUCCESS.

Parameters
fpc: The fused point cloud to be filled with the generated spatial map.
Returns
SUCCESS if the fused point cloud is retrieved, otherwise 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.

◆ extractWholeSpatialMap() [1/2]

ERROR_CODE extractWholeSpatialMap ( Mesh mesh)

Extracts the current spatial map from the spatial mapping process only if SpatialMappingParameters::map_type was set as SPATIAL_MAP_TYPE::MESH.

If the object to be filled already contains a previous version of the mesh, only changes will be updated, optimizing performance.

Parameters
mesh: The mesh to be filled with the generated spatial map.
Returns
SUCCESS if the mesh is filled and available, otherwise FAILURE.
Warning
This is a blocking function. You should either call it in a thread or at the end of the mapping process.
The extraction can be long, calling this function in the grab loop will block the depth and tracking computation giving bad results.
If the SpatialMappingParameters::map_type has not been setup as SPATIAL_MAP_TYPE::MESH, the object will be empty.
See enableSpatialMapping() for an example.

◆ extractWholeSpatialMap() [2/2]

ERROR_CODE extractWholeSpatialMap ( FusedPointCloud fpc)

Extracts the current spatial map from the spatial mapping process only if SpatialMappingParameters::map_type was set as SPATIAL_MAP_TYPE::FUSED_POINT_CLOUD.

If the object to be filled already contains a previous version of the fused point cloud, only changes will be updated, optimizing performance.

Parameters
fpc: The fused point cloud to be filled with the generated spatial map.
Returns
SUCCESS if the fused point cloud is filled and available, otherwise FAILURE.
Warning
This is a blocking function. You should either call it in a thread or at the end of the mapping process.
The extraction can be long, calling this function in the grab loop will block the depth and tracking computation giving bad results.
If the SpatialMappingParameters::map_type has not been setup as SPATIAL_MAP_TYPE::FUSED_POINT_CLOUD, the object will be empty.
See enableSpatialMapping() for an example.

◆ pauseSpatialMapping()

void pauseSpatialMapping ( bool  status)

Pauses or resumes the spatial mapping processes.

As spatial mapping runs asynchronously, using this function 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.

Parameters
status: if true, the integration is paused. If false, the spatial mapping is resumed.

◆ disableSpatialMapping()

void disableSpatialMapping ( )

Disables the spatial mapping process.

The spatial mapping is immediately stopped.
If the mapping has been enabled, this function will automatically be called by close().

Note
This function frees the memory allocated for the spatial mapping, consequently, the spatial map cannot be retrieved after this call.

◆ getSpatialMappingParameters()

SpatialMappingParameters getSpatialMappingParameters ( )

Returns the spatial mapping parameters used. Correspond to the structure send when the enableSpatialMapping() function was called.

Returns
SpatialMappingParameters containing the parameters used for spatial mapping intialization.

◆ findPlaneAtHit()

ERROR_CODE findPlaneAtHit ( sl::uint2  coord,
sl::Plane plane 
)

Checks the plane at the given left image coordinates.

This function 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.

Parameters
coord: [in] The image coordinate. The coordinate must be taken from the full-size image
plane: [out] The detected plane if the function succeeded
Returns
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() function.

◆ findFloorPlane()

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.

This function 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.

Parameters
floorPlane: [out] The detected floor plane if the function succeeded
resetTrackingFloorFrame: [out] 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: [in] 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 function will return ERROR_CODE::PLANE_NOT_FOUND
world_orientation_prior: [in] 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 function will return ERROR_CODE::PLANE_NOT_FOUND
floor_height_prior_tolerance: [in] Prior height tolerance, absolute value.
Returns
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() function. 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 the gravity as prior.

◆ enableRecording()

ERROR_CODE enableRecording ( RecordingParameters  recording_parameters)

Creates an SVO file to be filled by record().


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.

Parameters
recording_parameters: Recording parameters such as filename and compression mode
Returns
an ERROR_CODE that defines if SVO file was successfully created and can be filled with images.
Warning
This function can be called multiple times during ZED lifetime, but if video_filename is already existing, the file will be erased.
#include <sl/Camera.hpp>
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 != SUCCESS) {
std::cout << toString(err) << std::endl;
exit(-1);
}
// Enable video recording
err = zed.enableRecording(RecordingParameters("myVideoFile.svo", SVO_COMPRESSION_MODE::H264));
if (err != 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() == SUCCESS) {
// Record the grabbed frame in the video file
i++;
}
}
zed.disableRecording();
std::cout << "Video has been saved ..." << std::endl;
zed.close();
return 0;
}

◆ getRecordingStatus()

RecordingStatus getRecordingStatus ( )

Get the recording information.

Returns
The recording state structure. For more details, see RecordingStatus.

◆ pauseRecording()

void pauseRecording ( bool  status)

Pauses or resumes the recording.

Parameters
status: if true, the recording is paused. If false, the recording is resumed.

◆ disableRecording()

void disableRecording ( )

Disables the recording initiated by enableRecording() and closes the generated file.

Note
This function will automatically be called by close() if enableRecording() was called.

See enableRecording() for an example.

◆ getRecordingParameters()

RecordingParameters getRecordingParameters ( )

Returns the recording parameters used. Correspond to the structure send when the enableRecording() function was called.

Returns
RecordingParameters containing the parameters used for recording initialization.

◆ enableStreaming()

ERROR_CODE enableStreaming ( StreamingParameters  streaming_parameters = StreamingParameters())

Creates a streaming pipeline.

Parameters
streaming_parameters: the structure containing all the specific parameters for the streaming.
#include <sl/Camera.hpp>
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)
// Open the camera
ERROR_CODE err = zed.open(init_params);
if (err != SUCCESS) {
std::cout << toString(err) << std::endl;
exit(-1);
}
// Enable video recording
sl::StreamingParameters stream_params;
stream_params.port = 30000;
stream_params.bitrate = 8000;
err = zed.enableStreaming(stream_params);
if (err != 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() == SUCCESS) {
i++;
}
}
zed.disableStreaming();
zed.close();
return 0;
}
Sets the streaming parameters.
Definition: Camera.hpp:887
unsigned int bitrate
Defines the streaming bitrate in Kbits/s.
Definition: Camera.hpp:916
unsigned short port
Defines the port used for streaming.
Definition: Camera.hpp:899
Returns
an ERROR_CODE that defines if the stream was started.
Possible 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 RTP 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 sdk supports).

◆ disableStreaming()

void disableStreaming ( )

Disables the streaming initiated by enableStreaming()

Note
This function will automatically be called by close() if enableStreaming() was called. See enableStreaming() for an example.

◆ isStreamingEnabled()

bool isStreamingEnabled ( )

Tells if the streaming is running (true) or still initializing (false)

◆ getStreamingParameters()

StreamingParameters getStreamingParameters ( )

Returns the streaming parameters used. Correspond to the structure send when the enableStreaming() function was called.

Returns
StreamingParameters containing the parameters used for streaming initialization.

◆ enableObjectDetection()

ERROR_CODE enableObjectDetection ( ObjectDetectionParameters  object_detection_parameters = ObjectDetectionParameters())

Initializes and starts the Deep Learning detection module.
The object detection module currently supports two types of detection :

Detected objects can be retrieved using the retrieveObjects() function.

As detecting and tracking the objects is CPU and GPU-intensive, the module can be used synchronously or asynchronously using ObjectDetectionParameters::image_sync.

  • Synchronous: the retrieveObjects() function will be blocking during the detection.
  • Asynchronous: the detection is running in the background, and retrieveObjects() will immediately return the last objects detected.
Note
- Only one detection model can be used at the time.
- This Depth Learning detection module is only available for ZED2 cameras
- This feature uses AI to locate objects and requires a powerful GPU. A GPU with at least 3GB of memory is recommended.
Parameters
object_detection_parameters: Structure containing all specific parameters for object detection.
For more information, see the ObjectDetectionParameters documentation.
Returns
  • 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 (ZED Camera). the IMU gives the gravity vector that helps in the 3D box localization. Therefore the Object detection module is available only for ZED-M and ZED2 camera model.
  • ERROR_CODE::MOTION_SENSORS_REQUIRED : if the camera model is correct (ZED2) 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 ObjectDetection parameter is not compatible with other modules parameters (For example, depth mode has been set to NONE).
  • ERROR_CODE::FAILURE : otherwise.
    #include <sl/Camera.hpp>
    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 != SUCCESS) {
    std::cout << toString(err) << std::endl;
    exit(-1);
    }
    // Set the object detection parameters
    ObjectDetectionParameters object_detection_params;
    skeleton_params.image_sync = true;
    // Enable the object detection
    err = zed.enableObjectDetection(object_detection_params);
    if (err != SUCCESS) {
    std::cout << toString(err) << std::endl;
    exit(-1);
    }
    // Grab an image and detect objects on it
    Objects objects;
    while (true) {
    if (zed.grab() == 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;
    }

◆ pauseObjectDetection()

void pauseObjectDetection ( bool  status)

Pauses or resumes the object detection processes.

If the object detection has been enabled with ObjectDetectionParameters::image_sync set to false (running asynchronously), this function will pause processing.

While in pause, calling this function with status = false will resume the object detection. The retrieveObjects function will keep on returning the last objects detected while in pause.

Parameters
status: If true, object detection is paused. If false, object detection is resumed.

◆ disableObjectDetection()

void disableObjectDetection ( )

Disables the Object Detection process.

The object detection module immediately stops and frees its memory allocations. If the object detection has been enabled, this function will automatically be called by close().

◆ ingestCustomBoxObjects()

ERROR_CODE ingestCustomBoxObjects ( std::vector< CustomBoxObjectData > &  objects_in)

Feed the 3D Object tracking function with your own 2D bounding boxes from your own detection algorithm.

Note
The detection should be done on the current grabbed left image as the internal process will use all current available data to extract 3D informations and perform object tracking.

◆ retrieveObjects()

ERROR_CODE retrieveObjects ( Objects objects,
ObjectDetectionRuntimeParameters  parameters = ObjectDetectionRuntimeParameters() 
)

Retrieve objects detected by the object detection module.

This function returns the result of the object detection, whether the module is running synchronously or asynchronously.

  • Asynchronous: this function immediately returns the last objects detected. If the current detection isn't done, the objects from the last detection will be returned, and Objects::is_new will be set to false.
  • Synchronous: this function executes detection and waits for it to finish before returning the detected objects.

It is recommended to keep the same Objects object as the input of all calls to this function. This will enable the identification and the tracking of every objects detected.

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.
Returns
SUCCESS if everything went fine, ERROR_CODE::FAILURE otherwise
Objects objects; // Unique Objects to be updated after each grab
// --- Main loop
while (true) {
if (zed.grab() == SUCCESS) { // Grab an image from the camera
zed.retrieveObjects(objects);
for (auto object : objects.object_list) {
std::cout << object.label << std::endl;
}
}
}

◆ getObjectsBatch()

ERROR_CODE getObjectsBatch ( std::vector< sl::ObjectsBatch > &  trajectories)

Get a batch of detected objects.

Warning
This function need to be called after retrieveObjects, otherwise trajectories will be empty. This is the retrieveObjects function that ingest the current/live objects into the batching queue.
Parameters
trajectoriesas a std::vector of sl::ObjectBatch, that will be filled by the batching queue process.
Note
Most of the time, the vector will be empty and will be filled every BatchParameters::latency.
Returns
ERROR_CODE::SUCCESS if everything went fine.
ERROR_CODE::INVALID_FUNCTION_CALL if batching module is not available (TensorRT!=7.1) or if object tracking was not enabled.
Objects objects; // Unique Objects to be updated after each grab
// --- Main loop
while (true) {
if (zed.grab() == 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<sl::ObjectsBatch> traj_;
zed.getObjectsBatch(traj_);
std::cout<<" Size of batch : "<<traj_.size()<<std::endl;
// See zed-examples/object detection/birds eye viewer for a complete example.
}
}

◆ isObjectDetectionEnabled()

bool isObjectDetectionEnabled ( )

Tells if the object detection module is enabled.

◆ getObjectDetectionParameters()

ObjectDetectionParameters getObjectDetectionParameters ( )

Returns the object detection parameters used. Correspond to the structure send when the enableObjectDetection() function was called.

Returns
ObjectDetectionParameters containing the parameters used for object detection initialization.

◆ getCurrentMinMaxDepth()

ERROR_CODE getCurrentMinMaxDepth ( float &  min,
float &  max 
)

Gets the current range of perceived depth.

Parameters
min: [out] Minimum depth detected (in selected sl::UNIT)
max: [out] Maximum depth detected (in selected sl::UNIT)
Returns
ERROR_CODE::SUCCESS if values can be extracted, ERROR_CODE::FAILURE otherwise

◆ getSDKVersion() [1/2]

static String getSDKVersion ( )
static

Returns the version of the currently installed ZED SDK.

Returns
The ZED SDK version as a string with the following format : MAJOR.MINOR.PATCH
std::cout << Camera::getSDKVersion() << std::endl;
static String getSDKVersion()
Returns the version of the currently installed ZED SDK.

◆ getSDKVersion() [2/2]

static void getSDKVersion ( int &  major,
int &  minor,
int &  patch 
)
static

Returns the version of the currently installed ZED SDK.

Parameters
major: major int of the version filled
minor: minor int of the version filled
patch: patch int of the version filled
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;

◆ getDeviceList()

static std::vector<sl::DeviceProperties> getDeviceList ( )
static

List all the connected devices with their associated information.

This function lists all the cameras available and provides their serial number, models and other information.

Returns
The device properties for each connected camera
Warning
As this function 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.

◆ getStreamingDeviceList()

static std::vector<sl::StreamingProperties> getStreamingDeviceList ( )
static

List all the streaming devices with their associated information.

Returns
The streaming properties for each connected camera
Warning
As this function 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 function takes around 2seconds to make sure all network informations has been captured. Make sure to run this function in a thread.

◆ reboot()

static sl::ERROR_CODE reboot ( int  sn,
bool  fullReboot = true 
)
static

Performs an hardware reset of the ZED 2 and the ZED2i.

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.
Returns
SUCCESS if everything went fine, ERROR_CODE::CAMERA_NOT_DETECTED if no camera was detected, ERROR_CODE::FAILURE otherwise.
Note
This function only works for ZED 2, ZED 2i, and newer camera models.
Warning
This function 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 function while the camera is opened by another process will cause it to freeze for a few seconds while the device is rebooting.