InitParameters Class Reference

Holds the options used to initialize the Camera object.
Once passed to the Camera::open() function, these settings will be set for the entire execution life time of the Camera.
You can get further information in the detailed description bellow.
. More...

Functions

 InitParameters (RESOLUTION camera_resolution_=RESOLUTION::HD720, 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, bool sdk_verbose_=false, 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::AUTO, 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)
 Default constructor. All the parameters are set to their default and optimized values. More...
 
bool save (String filename)
 
bool load (String filename)
 
bool operator== (const InitParameters &param1) const
 
bool operator!= (const InitParameters &param1) const
 

Attributes

RESOLUTION camera_resolution
 
int camera_fps
 
int camera_image_flip
 
bool camera_disable_self_calib
 
bool enable_right_side_measure
 
bool svo_real_time_mode
 
DEPTH_MODE depth_mode
 
int depth_stabilization
 
float depth_minimum_distance
 
float depth_maximum_distance
 
UNIT coordinate_units
 
COORDINATE_SYSTEM coordinate_system
 
CUdevice sdk_gpu_id
 
int sdk_verbose
 
String sdk_verbose_log_file
 
CUcontext sdk_cuda_ctx
 
InputType input
 
String optional_settings_path
 
String optional_opencv_calibration_file
 
bool sensors_required
 
bool enable_image_enhancement
 
float open_timeout_sec
 

Detailed Description

Holds the options used to initialize the Camera object.
Once passed to the Camera::open() function, these settings will be set for the entire execution life time of the Camera.
You can get further information in the detailed description bellow.
.

This structure allows you to select multiple parameters for the 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 Camera::open function.

#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 = false; // 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 != SUCCESS)
exit(-1);
// Close the camera
zed.close();
return 0;
}
ERROR_CODE
Lists error codes in the ZED SDK.
Definition: types.hpp:368
Definition: defines.hpp:135
friend class Camera
Definition: Camera.hpp:124
InitParameters(RESOLUTION camera_resolution_=RESOLUTION::HD720, 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, bool sdk_verbose_=false, 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::AUTO, 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)
Default constructor. All the parameters are set to their default and optimized values.

With its default values, it opens the ZED camera in live mode at RESOLUTION::HD720 and sets the depth mode to DEPTH_MODE::PERFORMANCE.
You can customize it to fit your application. The parameters can also be saved and reloaded using its save() and load() functions.

Constructor and Destructor

◆ InitParameters()

InitParameters ( RESOLUTION  camera_resolution_ = RESOLUTION::HD720,
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,
bool  sdk_verbose_ = false,
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::AUTO,
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 
)

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

Functions

◆ save()

bool save ( String  filename)

This function saves the current set of parameters into a file to be reloaded with the load() function.

Parameters
filename: the 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, Function will return false and existing file will not be updated.
InitParameters init_params; // Set initial parameters
init_params.sdk_verbose = True; // 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)

This function set the other parameters from the values contained in a previously saved file.

Parameters
filename: the 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.

◆ 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

Define the chosen camera resolution. Small resolutions offer higher framerate and lower computation time.
In most situations, the RESOLUTION::HD720 at 60 fps is the best balance between image quality and framerate.
Available resolutions are listed here: RESOLUTION.
default : RESOLUTION::HD720

◆ camera_fps

int camera_fps

Requested camera frame rate. If set to 0, the highest FPS of the specified camera_resolution will be used.
See RESOLUTION for a list of supported framerates.
default : 0

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

◆ camera_image_flip

int camera_image_flip

If you are using the camera upside down, setting this parameter to FLIP_MODE::ON will cancel its rotation. The images will be horizontally flipped.
default : FLIP_MODE::AUTO From ZED SDK 3.2 a new FLIP_MODE enum was introduced to add the automatic flip mode detection based on the IMU gravity detection. This only works for ZED-M or ZED2 cameras.

◆ camera_disable_self_calib

bool camera_disable_self_calib

At initialization, the 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 conf 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 open() by calling Camera::UpdateSelfCalibration(), even if this parameter is set to true.

◆ enable_right_side_measure

bool enable_right_side_measure

By default, the SDK only computes a single depth map, aligned with the left camera image.
This parameter allows you to enable the MEASURE::DEPTH_RIGHT and other 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

When playing back an SVO file, each call to Camera::grab() will extract a new frame and use it.
However, this 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. However, calls to Camera::grab() will return an error when trying to play too fast, and frames will be dropped when playing too slowly.


default : false

◆ depth_mode

DEPTH_MODE depth_mode

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

◆ depth_stabilization

int depth_stabilization

Regions of the 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 control a stabilization filter that reduces these oscillations. In the range [0-100], 0 is disable (raw depth), 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.
Notice that calling Camera::enablePositionalTracking with your own parameters afterwards is still possible.

◆ depth_minimum_distance

float depth_minimum_distance

This parameter allows you to specify the minimum depth value (from the camera) that will be computed, measured in the UNIT you define.
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 of 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 to 700 mm for a ZED/ZED2 and 300 mm for ZED Mini.

Note
With a ZED camera you can decrease this value to 300 mm whereas you can set it to 100 mm using a ZED Mini and 200 mm for a ZED2. In any case this value cannot be greater than 3 meters.
Specific value (0) : This will set the depth minimum distance to the minimum authorized value :
  • 300mm for ZED
  • 100mm for ZED-M
  • 200mm for ZED2

◆ depth_maximum_distance

float depth_maximum_distance

Defines the current maximum distance that can be computed in the defined UNIT. When estimating the depth, the SDK uses this upper limit to turn higher values into TOO_FAR ones.

Note
Changing this value has no impact on performance and doesn't affect the positional tracking nor the spatial mapping. (Only the depth, point cloud, normals)

◆ coordinate_units

UNIT coordinate_units

This parameter allows you to select the unit to be used for all metric values of the SDK. (depth, point cloud, tracking, mesh, and others).
default : UNIT::MILLIMETER

◆ coordinate_system

COORDINATE_SYSTEM coordinate_system

Positional tracking, point clouds and many other features require a given COORDINATE_SYSTEM to be used as reference. This parameter allows you to select the COORDINATE_SYSTEM used by the Camera to return its measures.
This defines the order and the direction of the axis of the coordinate system.
default : COORDINATE_SYSTEM::IMAGE

◆ sdk_gpu_id

CUdevice sdk_gpu_id

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

This parameter allows you to enable the verbosity of the 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 SDK behavior.
However, this might not be desirable in a shipped version.
default : 0 = no verbose message

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

When sdk_verbose is enabled, this parameter allows you to redirect both the SDK verbose messages and your own application messages to a file.
default : (empty) Should contain the path to the file to be written. A file will be created if missing.

Note
Setting this parameter to any value will redirect all std::cout calls of the entire program. This means that your own std::cout 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

If your application uses another CUDA-capable library, giving its CUDA context to the SDK can be useful when sharing GPU memories.
This parameter allows you to set the CUDA context to be used by the 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 Camera::getCUDAContext() to use it.

◆ input

InputType input

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)
  • Select a camera by its serial number
  • Open a recorded sequence in the SVO file format
  • Open a streaming camera from its IP address and port

This parameter allows you to select to desired input. It should be used like this:

InitParameters init_params; // Set initial parameters
init_params.sdk_verbose = True; // Enable verbose mode
init_params.input.setFromCameraID(0); // Selects the camera with ID = 0
InitParameters init_params; // Set initial parameters
init_params.sdk_verbose = True; // Enable verbose mode
init_params.input.setFromSerialNumber(1010); // Selects the camera with serial number = 1010
InitParameters init_params; // Set initial parameters
init_params.sdk_verbose = True; // Enable verbose mode
init_params.input.setFromSVOFile("/path/to/file.svo"); // Selects the and SVO file to be read
InitParameters init_params; // Set initial parameters
init_params.sdk_verbose = True; // 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.


Available cameras and their ID/serial can be listed using Camera::getDeviceList and Camera::getStreamingDeviceList.
Each Camera will create its own memory (CPU and GPU), therefore the number of ZED used at the same time can be limited by the configuration of your computer. (GPU/CPU memory and capabilities)
default : (empty)
See InputType for complementary information.

◆ optional_settings_path

String optional_settings_path

Set the optional path where the SDK has to search for the settings file (SN<XXXX>.conf file). This file contains the calibration information of the camera.
default : (empty). The SNXXX.conf file will be searched in the default directory (/usr/local/zed/settings/ for Linux or C:/ProgramData/stereolabs/settings for Windows)

Note
if a path is specified and no file has been found, the SDK will search on the default path (see default) for the *.conf file.
Automatic download of conf file (through ZED Explorer or the installer) will still download the files on the default path. If you want to use another path by using this entry, make sure to copy the file in the proper location.
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());
Defines a string.
Definition: types.hpp:145

◆ optional_opencv_calibration_file

String optional_opencv_calibration_file

Set an optional file path where the 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 contains the following key :
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 SDK modules.

◆ sensors_required

bool sensors_required

Force the motion sensors opening of the ZED 2 / ZED-M to open the camera.
default : false.
If set to false, the 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).
This parameter only impacts the LIVE mode.
If set to true, the camera will fail to open 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 ZED camera since it does not include sensors.

◆ enable_image_enhancement

bool enable_image_enhancement

Enable or Disable 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.
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 open() command 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.
This parameter only impacts the LIVE mode.
default : 5.0f