InitParameters Class Reference

Class containing the options used to initialize the sl::Camera object. More...

Functions

 InitParameters (RESOLUTION camera_resolution_=RESOLUTION::AUTO, int camera_fps_=0, bool svo_real_time_mode_=false, DEPTH_MODE depth_mode_=DEPTH_MODE::ULTRA, UNIT coordinate_units_=UNIT::MILLIMETER, COORDINATE_SYSTEM coordinate_system_=COORDINATE_SYSTEM::IMAGE, int sdk_verbose_=1, int sdk_gpu_id_=-1, float depth_minimum_distance_=-1., float depth_maximum_distance_=-1., bool camera_disable_self_calib_=false, int camera_image_flip_=FLIP_MODE::OFF, bool enable_right_side_measure_=false, String sdk_verbose_log_file_=String(), int depth_stabilization_=1, CUcontext sdk_cuda_ctx_=CUcontext(), InputType input_type=InputType(), String optional_settings_path_=String(), bool sensors_required_=false, bool enable_image_enhancement_=true, String optional_opencv_calibration_file_=String(), float open_timeout_sec_=5.0f, bool async_grab_camera_recovery=false, float grab_compute_capping_fps=0, int enable_image_validity_check=false, bool async_image_retrieval=false)
 Default constructor. More...
 
bool save (String filename, SERIALIZATION_FORMAT format=SERIALIZATION_FORMAT::LEGACY) const
 Saves the current set of parameters into a file to be reloaded with the load() method. More...
 
bool load (String filename, SERIALIZATION_FORMAT format=SERIALIZATION_FORMAT::AUTO)
 Loads a set of parameters from the values contained in a previously saved file. More...
 
bool encode (String &serialized_content, SERIALIZATION_FORMAT format=SERIALIZATION_FORMAT::JSON) const
 Generate a JSON Object (with the struct type as a key) containing the serialized struct, converted into a string. More...
 
bool decode (const String &serialized_content, SERIALIZATION_FORMAT format=SERIALIZATION_FORMAT::JSON)
 Fill the structure from the serialized json object contained in the input string. More...
 
bool operator== (const InitParameters &param1) const
 Comparison operator ==. More...
 
bool operator!= (const InitParameters &param1) const
 Comparison operator !=. More...
 

Attributes

RESOLUTION camera_resolution
 Desired camera resolution. More...
 
int camera_fps
 Requested camera frame rate. More...
 
int camera_image_flip
 Defines if a flip of the images is needed. More...
 
bool camera_disable_self_calib
 Disables the self-calibration process at camera opening. More...
 
bool enable_right_side_measure
 Enable the measurement computation on the right images. More...
 
bool svo_real_time_mode
 Defines if sl::Camera object return the frame in real time mode. More...
 
DEPTH_MODE depth_mode
 sl::DEPTH_MODE to be used. More...
 
int depth_stabilization
 Defines whether the depth needs to be stabilized and to what extent. More...
 
float depth_minimum_distance
 Minimum depth distance to be returned, measured in the sl::UNIT defined in coordinate_units. More...
 
float depth_maximum_distance
 Maximum depth distance to be returned, measured in the sl::UNIT defined in coordinate_units. More...
 
UNIT coordinate_units
 Unit of spatial data (depth, point cloud, tracking, mesh, etc.) for retrieval. More...
 
COORDINATE_SYSTEM coordinate_system
 sl::COORDINATE_SYSTEM to be used as reference for positional tracking, mesh, point clouds, etc. More...
 
CUdevice sdk_gpu_id
 NVIDIA graphics card to use. More...
 
int sdk_verbose
 Enable the ZED SDK verbose mode. More...
 
String sdk_verbose_log_file
 File path to store the ZED SDK logs (if sdk_verbose is enabled). More...
 
CUcontext sdk_cuda_ctx
 CUcontext to be used. More...
 
InputType input
 Defines the input source to initialize and open an sl::Camera object from. More...
 
String optional_settings_path
 Optional path where the ZED SDK has to search for the settings file (SN<XXXX>.conf file). More...
 
String optional_opencv_calibration_file
 Optional path where the ZED SDK can find a file containing the calibration information of the camera computed by OpenCV. More...
 
bool sensors_required
 Requires the successful opening of the motion sensors before opening the camera. More...
 
bool enable_image_enhancement
 Enable the Enhanced Contrast Technology, to improve image quality. More...
 
float open_timeout_sec
 Define a timeout in seconds after which an error is reported if the sl::Camera::open() method fails. More...
 
bool async_grab_camera_recovery
 Define the behavior of the automatic camera recovery during sl::Camera::grab() method call. More...
 
float grab_compute_capping_fps
 Define a computation upper limit to the grab frequency. More...
 
bool async_image_retrieval
 If set to true will camera image retrieve at a framerate different from grab() application framerate. This is useful for recording SVO or sending camera stream at different rate than application. More...
 
int enable_image_validity_check
 Enable or disable the image validity verification. More...
 

Detailed Description

Class containing the options used to initialize the sl::Camera object.

This class allows you to select multiple parameters for the sl::Camera such as the selected camera, resolution, depth mode, coordinate system, and units of measurement.
Once filled with the desired options, it should be passed to the sl::Camera.open() method.

#include <sl/Camera.hpp>
using namespace sl;
int main(int argc, char **argv) {
Camera zed; // Create a ZED camera object
InitParameters init_params; // Set initial parameters
init_params.sdk_verbose = 0; // Disable verbose mode
// Use the camera in LIVE mode
init_params.camera_resolution = RESOLUTION::HD1080; // Use HD1080 video mode
init_params.camera_fps = 30; // Set fps at 30
// Or use the camera in SVO (offline) mode
//init_params.input.setFromSVOFile("xxxx.svo");
// Or use the camera in STREAM mode
//init_params.input.setFromStream("192.168.1.12",30000);
// Other parameters are left to their default values
// Open the camera
ERROR_CODE err = zed.open(init_params);
if (err != ERROR_CODE::SUCCESS)
exit(-1);
// Close the camera
zed.close();
return 0;
}
ERROR_CODE
Lists error codes in the ZED SDK.
Definition: types.hpp:482
Definition: defines.hpp:58
InitParameters(RESOLUTION camera_resolution_=RESOLUTION::AUTO, int camera_fps_=0, bool svo_real_time_mode_=false, DEPTH_MODE depth_mode_=DEPTH_MODE::ULTRA, UNIT coordinate_units_=UNIT::MILLIMETER, COORDINATE_SYSTEM coordinate_system_=COORDINATE_SYSTEM::IMAGE, int sdk_verbose_=1, int sdk_gpu_id_=-1, float depth_minimum_distance_=-1., float depth_maximum_distance_=-1., bool camera_disable_self_calib_=false, int camera_image_flip_=FLIP_MODE::OFF, bool enable_right_side_measure_=false, String sdk_verbose_log_file_=String(), int depth_stabilization_=1, CUcontext sdk_cuda_ctx_=CUcontext(), InputType input_type=InputType(), String optional_settings_path_=String(), bool sensors_required_=false, bool enable_image_enhancement_=true, String optional_opencv_calibration_file_=String(), float open_timeout_sec_=5.0f, bool async_grab_camera_recovery=false, float grab_compute_capping_fps=0, int enable_image_validity_check=false, bool async_image_retrieval=false)
Default constructor.
friend class Camera
Definition: Camera.hpp:72

With its default values, it opens the camera in live mode at sl::RESOLUTION::HD720 (or sl::RESOLUTION::HD1200 for the ZED X/X Mini) and sets the depth mode to sl::DEPTH_MODE::ULTRA (or sl::DEPTH_MODE::PERFORMANCE on Jetson).
You can customize it to fit your application.

Note
The parameters can also be saved and reloaded using its save() and load() methods.

Constructor and Destructor

◆ InitParameters()

InitParameters ( RESOLUTION  camera_resolution_ = RESOLUTION::AUTO,
int  camera_fps_ = 0,
bool  svo_real_time_mode_ = false,
DEPTH_MODE  depth_mode_ = DEPTH_MODE::ULTRA,
UNIT  coordinate_units_ = UNIT::MILLIMETER,
COORDINATE_SYSTEM  coordinate_system_ = COORDINATE_SYSTEM::IMAGE,
int  sdk_verbose_ = 1,
int  sdk_gpu_id_ = -1,
float  depth_minimum_distance_ = -1.,
float  depth_maximum_distance_ = -1.,
bool  camera_disable_self_calib_ = false,
int  camera_image_flip_ = FLIP_MODE::OFF,
bool  enable_right_side_measure_ = false,
String  sdk_verbose_log_file_ = String(),
int  depth_stabilization_ = 1,
CUcontext  sdk_cuda_ctx_ = CUcontext(),
InputType  input_type = InputType(),
String  optional_settings_path_ = String(),
bool  sensors_required_ = false,
bool  enable_image_enhancement_ = true,
String  optional_opencv_calibration_file_ = String(),
float  open_timeout_sec_ = 5.0f,
bool  async_grab_camera_recovery = false,
float  grab_compute_capping_fps = 0,
int  enable_image_validity_check = false,
bool  async_image_retrieval = false 
)

Default constructor.

All the parameters are set to their default and optimized values.

Functions

◆ save()

bool save ( String  filename,
SERIALIZATION_FORMAT  format = SERIALIZATION_FORMAT::LEGACY 
) const

Saves the current set of parameters into a file to be reloaded with the load() method.

Parameters
filename: Name of the file which will be created to store the parameters (extension '.yml' will be added if not set).
Returns
True if file was successfully saved, otherwise false.
Warning
For security reason, the file must not exist.
In case a file already exists, the method will return false and existing file will not be updated.
InitParameters init_params; // Set initial parameters
init_params.sdk_verbose = 1; // Enable verbose mode
init_params.input.setFromSVOFile("/path/to/file.svo"); // Selects the and SVO file to be read
init_params.save("initParameters.yml"); // Export the parameters into a file

◆ load()

bool load ( String  filename,
SERIALIZATION_FORMAT  format = SERIALIZATION_FORMAT::AUTO 
)

Loads a set of parameters from the values contained in a previously saved file.

Parameters
filename: Path to the file from which the parameters will be loaded (extension '.yml' will be added at the end of the filename if not set).
Returns
True if the file was successfully loaded, otherwise false.
InitParameters init_params; // Set initial parameters
init_params.load("initParameters.yml"); // Load the init_params from a previously exported file
Note
As the InitParameters files can be easily modified manually (using a text editor) this function allows you to test various settings without re-compiling your application.

◆ encode()

bool encode ( String serialized_content,
SERIALIZATION_FORMAT  format = SERIALIZATION_FORMAT::JSON 
) const

Generate a JSON Object (with the struct type as a key) containing the serialized struct, converted into a string.

Parameters
serialized_contentoutput string containing the JSON Object
formatserialization format, default is JSON
Returns
True if file was successfully saved, otherwise false.

◆ decode()

bool decode ( const String serialized_content,
SERIALIZATION_FORMAT  format = SERIALIZATION_FORMAT::JSON 
)

Fill the structure from the serialized json object contained in the input string.

Parameters
serialized_contentinput string containing the JSON Object
formatserialization format, default is JSON
Returns
True if the decoding was successful, otherwise false.

◆ operator==()

bool operator== ( const InitParameters param1) const

Comparison operator ==.

Parameters
InitParametersto compare
Returns
true if the two struct are identical

◆ operator!=()

bool operator!= ( const InitParameters param1) const

Comparison operator !=.

Parameters
InitParametersto compare
Returns
true if the two struct are different

Variables

◆ camera_resolution

RESOLUTION camera_resolution

Desired camera resolution.

Note
Small resolutions offer higher framerate and lower computation time.
In most situations, sl::RESOLUTION::HD720 at 60 FPS is the best balance between image quality and framerate.

Default:

Note
Available resolutions are listed here: sl::RESOLUTION.

◆ camera_fps

int camera_fps

Requested camera frame rate.

If set to 0, the highest FPS of the specified camera_resolution will be used.
Default: 0

See sl::RESOLUTION for a list of supported frame rates.

Note
If the requested camera_fps is unsupported, the closest available FPS will be used.

◆ camera_image_flip

int camera_image_flip

Defines if a flip of the images is needed.

If you are using the camera upside down, setting this parameter to sl::FLIP_MODE::ON will cancel its rotation.
The images will be horizontally flipped.
Default: sl::FLIP_MODE::AUTO

Note
From ZED SDK 3.2 a new sl::FLIP_MODE enum was introduced to add the automatic flip mode detection based on the IMU gravity detection.
This does not work on sl::MODEL::ZED cameras since they do not have the necessary sensors.

◆ camera_disable_self_calib

bool camera_disable_self_calib

Disables the self-calibration process at camera opening.

At initialization, sl::Camera runs a self-calibration process that corrects small offsets from the device's factory calibration.
A drawback is that calibration parameters will slightly change from one (live) run to another, which can be an issue for repeatability.
If set to true, self-calibration will be disabled and calibration parameters won't be optimized, raw calibration parameters from the configuration file will be used.
Default: false

Note
In most situations, self calibration should remain enabled.
You can also trigger the self-calibration at anytime after sl::Camera::open() by calling sl::Camera::updateSelfCalibration(), even if this parameter is set to true.

◆ enable_right_side_measure

bool enable_right_side_measure

Enable the measurement computation on the right images.

By default, the ZED SDK only computes a single depth map, aligned with the left camera image.
This parameter allows you to enable sl::MEASURE::DEPTH_RIGHT and other sl::MEASURE::XXX_RIGHT at the cost of additional computation time.
For example, mixed reality pass-through applications require one depth map per eye, so this parameter can be activated.
Default: false

◆ svo_real_time_mode

bool svo_real_time_mode

Defines if sl::Camera object return the frame in real time mode.

When playing back an SVO file, each call to sl::Camera::grab() will extract a new frame and use it.
However, it ignores the real capture rate of the images saved in the SVO file.
Enabling this parameter will bring the SDK closer to a real simulation when playing back a file by using the images' timestamps.
Default: false

Note
sl::Camera::grab() will return an error when trying to play too fast, and frames will be dropped when playing too slowly.

◆ depth_mode

DEPTH_MODE depth_mode

sl::DEPTH_MODE to be used.

The ZED SDK offers several sl::DEPTH_MODE, offering various levels of performance and accuracy.
This parameter allows you to set the sl::DEPTH_MODE that best matches your needs.
Default: sl::DEPTH_MODE::PERFORMANCE

Note
Available depth mode are listed here: sl::DEPTH_MODE.

◆ depth_stabilization

int depth_stabilization

Defines whether the depth needs to be stabilized and to what extent.

Regions of generated depth map can oscillate from one frame to another.
These oscillations result from a lack of texture (too homogeneous) on an object and by image noise.
This parameter controls a stabilization filter that reduces these oscillations.
In the range [0-100]:

  • 0 disable the depth stabilization (raw depth will be return)
  • stabilization smoothness is linear from 1 to 100

Default: 1

Note
The stabilization uses the positional tracking to increase its accuracy, so the positional tracking module will be enabled automatically when set to a value different from 0.
Note that calling sl::Camera::enablePositionalTracking() with your own parameters afterwards is still possible.

◆ depth_minimum_distance

float depth_minimum_distance

Minimum depth distance to be returned, measured in the sl::UNIT defined in coordinate_units.

This parameter allows you to specify the minimum depth value (from the camera) that will be computed.


In stereovision (the depth technology used by the camera), looking for closer depth values can have a slight impact on performance and memory consumption.
On most modern GPUs, performance impact will be low. However, the impact of memory footprint will be visible.
In cases of limited computation power, increasing this value can provide better performance.
Default: -1 (corresponding values are available here)

Note
depth_minimum_distance value cannot be greater than 3 meters.
0 will imply that depth_minimum_distance is set to the minimum depth possible for each camera (those values are available here).

◆ depth_maximum_distance

float depth_maximum_distance

Maximum depth distance to be returned, measured in the sl::UNIT defined in coordinate_units.

When estimating the depth, the ZED SDK uses this upper limit to turn higher values into sl::TOO_FAR ones.

Note
Changing this value has no impact on performance and doesn't affect the positional tracking nor the spatial mapping.
It only change values the depth, point cloud and normals.

◆ coordinate_units

UNIT coordinate_units

Unit of spatial data (depth, point cloud, tracking, mesh, etc.) for retrieval.

Default: sl::UNIT::MILLIMETER

◆ coordinate_system

COORDINATE_SYSTEM coordinate_system

sl::COORDINATE_SYSTEM to be used as reference for positional tracking, mesh, point clouds, etc.

This parameter allows you to select the sl::COORDINATE_SYSTEM used by the sl::Camera object to return its measures.
This defines the order and the direction of the axis of the coordinate system.
Default: sl::COORDINATE_SYSTEM::IMAGE

◆ sdk_gpu_id

CUdevice sdk_gpu_id

NVIDIA graphics card to use.

By default the SDK will use the most powerful NVIDIA graphics card found.
However, when running several applications, or using several cameras at the same time, splitting the load over available GPUs can be useful.
This parameter allows you to select the GPU used by the sl::Camera using an ID from 0 to n-1 GPUs in your PC.
Default: -1

Note
A non-positive value will search for all CUDA capable devices and select the most powerful.

◆ sdk_verbose

int sdk_verbose

Enable the ZED SDK verbose mode.

This parameter allows you to enable the verbosity of the ZED SDK to get a variety of runtime information in the console.
When developing an application, enabling verbose (sdk_verbose >= 1) mode can help you understand the current ZED SDK behavior.
However, this might not be desirable in a shipped version.
Default: 1 (verbose message enabled)

Note
The verbose messages can also be exported into a log file.
See sdk_verbose_log_file for more.

◆ sdk_verbose_log_file

String sdk_verbose_log_file

File path to store the ZED SDK logs (if sdk_verbose is enabled).

The file will be created if it does not exist.
Default: ""

Note
Setting this parameter to any value will redirect all standard output print calls of the entire program.
This means that your own standard output print calls will be redirected to the log file.
This parameter can be particularly useful for creating a log system, and with Unreal or Unity applications that don't provide a standard console output.
Warning
The log file won't be cleared after successive executions of the application.
This means that it can grow indefinitely if not cleared.

◆ sdk_cuda_ctx

CUcontext sdk_cuda_ctx

CUcontext to be used.

If your application uses another CUDA-capable library, giving its CUDA context to the ZED SDK can be useful when sharing GPU memories.
This parameter allows you to set the CUDA context to be used by the ZED SDK.
Leaving this parameter empty asks the SDK to create its own context.
Default: (empty)

Note
When creating you own CUDA context, you have to define the device you will use. Do not forget to also specify it on sdk_gpu_id.
On Jetson, you have to set the flag CU_CTX_SCHED_YIELD, during CUDA context creation.
You can also let the SDK create its own context, and use sl::Camera::getCUDAContext() to use it.

◆ input

InputType input

Defines the input source to initialize and open an sl::Camera object from.

The SDK can handle different input types:

  • Select a camera by its ID (/dev/videoX on Linux, and 0 to N cameras connected on Windows)
    InitParameters init_params; // Set initial parameters
    init_params.sdk_verbose = 1; // Enable verbose mode
    init_params.input.setFromCameraID(0); // Selects the camera with ID = 0
  • Select a camera by its serial number
    InitParameters init_params; // Set initial parameters
    init_params.sdk_verbose = 1; // Enable verbose mode
    init_params.input.setFromSerialNumber(1010); // Selects the camera with serial number = 1010
  • Open a recorded sequence in the SVO file format
    InitParameters init_params; // Set initial parameters
    init_params.sdk_verbose = 1; // Enable verbose mode
    init_params.input.setFromSVOFile("/path/to/file.svo"); // Selects the and SVO file to be read
  • Open a streaming camera from its IP address and port
    InitParameters init_params; // Set initial parameters
    init_params.sdk_verbose = 1; // Enable verbose mode
    init_params.input.setFromStream("192.168.1.42"); // Selects the IP address of the streaming camera. A second optional parameter is available for port selection.
Note
Available cameras and their id/serial number can be listed using sl::Camera::getDeviceList() and sl::Camera::getStreamingDeviceList().
Each sl::Camera will create its own memory (CPU and GPU), therefore the number of cameras used at the same time can be limited by the configuration of your computer (GPU/CPU memory and capabilities).

Default : (empty)

Note
See sl::InputType for complementary information.

◆ optional_settings_path

String optional_settings_path

Optional path where the ZED SDK has to search for the settings file (SN<XXXX>.conf file).

This file contains the calibration information of the camera.
Default: ""

Note
The settings file will be searched in the default directory:
  • Linux: /usr/local/zed/settings/
  • Windows: C:/ProgramData/stereolabs/settings
If a path is specified and no file has been found, the ZED SDK will search the settings file in the default directory.
An automatic download of the settings file (through ZED Explorer or the installer) will still download the files on the default path.
InitParameters init_params; // Set initial parameters
std::string home = getenv("HOME"); // Get /home/user as string using getenv()
std::string path = home + "/Documents/settings/"; // Assuming /home/<user>/Documents/settings/SNXXXX.conf exists. Otherwise, it will be searched in /usr/local/zed/settings/
init_params.optional_settings_path = sl::String(path.c_str());
Class defining a string.
Definition: types.hpp:146

◆ optional_opencv_calibration_file

String optional_opencv_calibration_file

Optional path where the ZED SDK can find a file containing the calibration information of the camera computed by OpenCV.

Note
Using this will disable the factory calibration of the camera.
The file must be in a XML/YAML/JSON formatting provided by OpenCV.
It also must contain the following keys: Size, K_LEFT (intrinsic left), K_RIGHT (intrinsic right), D_LEFT (distortion left), D_RIGHT (distortion right), R (extrinsic rotation), T (extrinsic translation).
Warning
Erroneous calibration values can lead to poor accuracy in all ZED SDK modules.

◆ sensors_required

bool sensors_required

Requires the successful opening of the motion sensors before opening the camera.

Default: false.

Note
If set to false, the ZED SDK will try to open and use the IMU (second USB device on USB2.0) and will open the camera successfully even if the sensors failed to open.

This can be used for example when using a USB3.0 only extension cable (some fiber extension for example).

Note
This parameter only impacts the LIVE mode.
If set to true, sl::Camera::open() will fail if the sensors cannot be opened.
This parameter should be used when the IMU data must be available, such as object detection module or when the gravity is needed.


Note
This setting is not taken into account for sl::MODEL::ZED camera since it does not include sensors.

◆ enable_image_enhancement

bool enable_image_enhancement

Enable the Enhanced Contrast Technology, to improve image quality.

Default: true.


If set to true, image enhancement will be activated in camera ISP. Otherwise, the image will not be enhanced by the IPS.

Note
This only works for firmware version starting from 1523 and up.

◆ open_timeout_sec

float open_timeout_sec

Define a timeout in seconds after which an error is reported if the sl::Camera::open() method fails.

Set to '-1' to try to open the camera endlessly without returning error in case of failure.
Set to '0' to return error in case of failure at the first attempt.
Default: 5.0

Note
This parameter only impacts the LIVE mode.

◆ async_grab_camera_recovery

bool async_grab_camera_recovery

Define the behavior of the automatic camera recovery during sl::Camera::grab() method call.

When async is enabled and there's an issue with the communication with the sl::Camera object, sl::Camera::grab() will exit after a short period and return the sl::ERROR_CODE::CAMERA_REBOOTING warning.
The recovery will run in the background until the correct communication is restored.
When async_grab_camera_recovery is false, the sl::Camera::grab() method is blocking and will return only once the camera communication is restored or the timeout is reached.
Default: false

◆ grab_compute_capping_fps

float grab_compute_capping_fps

Define a computation upper limit to the grab frequency.

This can be useful to get a known constant fixed rate or limit the computation load while keeping a short exposure time by setting a high camera capture framerate.
The value should be inferior to the sl::InitParameters.camera_fps and strictly positive.

Note
It has no effect when reading an SVO file.

This is an upper limit and won't make a difference if the computation is slower than the desired compute capping FPS.

Note
Internally the sl::Camera::grab() method always tries to get the latest available image while respecting the desired FPS as much as possible.

◆ async_image_retrieval

bool async_image_retrieval

If set to true will camera image retrieve at a framerate different from grab() application framerate. This is useful for recording SVO or sending camera stream at different rate than application.

◆ enable_image_validity_check

int enable_image_validity_check

Enable or disable the image validity verification.

This will perform additional verification on the image to identify corrupted data. This verification is done in the sl::Camera.grab() method and requires some computations.
If an issue is found, the sl::Camera.grab() method will output a warning as sl::ERROR_CODE::CORRUPTED_FRAME.
This version doesn't detect frame tearing currently.
Default: false (disabled)