InitParametersOne Class Reference

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

Attributes

sl::RESOLUTION camera_resolution = sl::RESOLUTION::AUTO
 Desired camera resolution. More...
 
int camera_fps = 0
 Requested camera frame rate. More...
 
int camera_image_flip = 0
 Defines if a flip of the images is needed. More...
 
bool svo_real_time_mode = true
 Defines if SVO playback will return frame to fit the real time. More...
 
sl::UNIT coordinate_units = sl::UNIT::MILLIMETER
 Unit of spatial data . Default: sl::UNIT::MILLIMETER. More...
 
sl::COORDINATE_SYSTEM coordinate_system = sl::COORDINATE_SYSTEM::IMAGE
 sl::COORDINATE_SYSTEM to be used as reference for positional tracking, mesh, point clouds, etc. More...
 
CUcontext sdk_cuda_ctx
 CUcontext to be used. More...
 
int sdk_verbose = 0
 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...
 
InputType input
 Defines the input source to initialize and open an sl::CameraOne 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...
 
float open_timeout_sec = 5.f
 Define a timeout in seconds after which an error is reported if the sl::CameraOne::open() method fails. More...
 
bool async_grab_camera_recovery = false
 Define the behavior of the automatic camera recovery during sl::CameraOne::grab() method call. More...
 
bool enable_hdr = false
 Define the HDR mode when available. More...
 

Detailed Description

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

This class allows you to select parameters for the sl::CameraOne such as its input, live or playback, its resolution, its frame rate...
Once filled with the desired options, it should be passed to the sl::CameraOne.open() method.
You can customize it to fit your application.

Variables

◆ camera_resolution

sl::RESOLUTION camera_resolution = sl::RESOLUTION::AUTO

Desired camera resolution.

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

◆ camera_fps

int camera_fps = 0

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

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

◆ svo_real_time_mode

bool svo_real_time_mode = true

Defines if SVO playback will return frame to fit the real time.

When playing back an SVO file, each call to sl::CameraOne::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::CameraOne::grab() will return an error when trying to play too fast, and frames will be dropped when playing too slowly.

◆ coordinate_units

sl::UNIT coordinate_units = sl::UNIT::MILLIMETER

Unit of spatial data . Default: sl::UNIT::MILLIMETER.

◆ 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::CameraOne 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_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.

◆ sdk_verbose

int sdk_verbose = 0

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.

◆ input

InputType input

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

The SDK can handle different input types:

  • Select a camera by its ID (only take care of ZED-X-One camera)
    InitParametersOne init_params; // Set initial parameters
    init_params.input.setFromCameraID(0); // Selects the camera with ID = 0
  • Select a camera by its serial number
    InitParametersOne init_params; // Set initial parameters
    init_params.input.setFromSerialNumber(1010); // Selects the camera with serial number = 1010
  • Open a recorded sequence in the SVO file format
    InitParametersOne init_params; // Set initial parameters
    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
    InitParametersOne init_params; // Set initial parameters
    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::CameraOne::getDeviceList() and sl::CameraOne::getStreamingDeviceList().
Each sl::CameraOne 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.

◆ open_timeout_sec

float open_timeout_sec = 5.f

Define a timeout in seconds after which an error is reported if the sl::CameraOne::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 = false

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

When async is enabled and there's an issue with the communication with the sl::CameraOne object, sl::CameraOne::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::CameraOne::grab() method is blocking and will return only once the camera communication is restored or the timeout is reached.
Default: false

◆ enable_hdr

bool enable_hdr = false

Define the HDR mode when available.

When set to true, the camera will be set in HDR mode if the camera model and resolution allows it.
Otherwise, the camera will be fallback to a compatible mode.
HDR (High Dynamic Range) enhances image quality in scenes with high contrast, providing greater detail in both the brightest and darkest areas.
Default: false