InitParameters Class Reference

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

Functions

InitParameters __cinit__ (self, camera_resolution=RESOLUTION.AUTO, camera_fps=0, svo_real_time_mode=False, depth_mode=DEPTH_MODE.PERFORMANCE, coordinate_units=UNIT.MILLIMETER, coordinate_system=COORDINATE_SYSTEM.IMAGE, sdk_verbose=1, sdk_gpu_id=-1, depth_minimum_distance=-1.0, depth_maximum_distance=-1.0, camera_disable_self_calib=False, camera_image_flip=FLIP_MODE.OFF, enable_right_side_measure=False, sdk_verbose_log_file="", depth_stabilization=1, input_t=InputType(), optional_settings_path="", sensors_required=False, enable_image_enhancement=True, optional_opencv_calibration_file="", open_timeout_sec=5.0, async_grab_camera_recovery=False, grab_compute_capping_fps=0, enable_image_validity_check=False)
 Default constructor. More...
 
bool save (self, str filename)
 Saves the current set of parameters into a file to be reloaded with the load() method. More...
 
bool load (self, str filename)
 Loads a set of parameters from the values contained in a previously saved file. More...
 
RESOLUTION camera_resolution (self)
 Desired camera resolution. More...
 
int camera_fps (self)
 Requested camera frame rate. More...
 
bool sensors_required (self)
 Requires the successful opening of the motion sensors before opening the camera. More...
 
bool enable_image_enhancement (self)
 Enable the Enhanced Contrast Technology, to improve image quality. More...
 
bool svo_real_time_mode (self)
 Defines if sl.Camera object return the frame in real time mode. More...
 
DEPTH_MODE depth_mode (self)
 sl.DEPTH_MODE to be used. More...
 
UNIT coordinate_units (self)
 Unit of spatial data (depth, point cloud, tracking, mesh, etc.) for retrieval. More...
 
COORDINATE_SYSTEM coordinate_system (self)
 sl.COORDINATE_SYSTEM to be used as reference for positional tracking, mesh, point clouds, etc. More...
 
int sdk_verbose (self)
 Enable the ZED SDK verbose mode. More...
 
int sdk_gpu_id (self)
 NVIDIA graphics card id to use. More...
 
float depth_minimum_distance (self)
 Minimum depth distance to be returned, measured in the sl.UNIT defined in coordinate_units. More...
 
float depth_maximum_distance (self)
 Maximum depth distance to be returned, measured in the sl.UNIT defined in coordinate_units. More...
 
bool camera_disable_self_calib (self)
 Disables the self-calibration process at camera opening. More...
 
FLIP_MODE camera_image_flip (self)
 Defines if a flip of the images is needed. More...
 
bool enable_right_side_measure (self)
 Enable the measurement computation on the right images. More...
 
str sdk_verbose_log_file (self)
 File path to store the ZED SDK logs (if sdk_verbose is enabled). More...
 
int depth_stabilization (self)
 Defines whether the depth needs to be stabilized and to what extent. More...
 
str optional_settings_path (self)
 Optional path where the ZED SDK has to search for the settings file (SN<XXXX>.conf file). More...
 
str optional_opencv_calibration_file (self)
 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 (self)
 Define a timeout in seconds after which an error is reported if the sl.Camera.open() method fails. More...
 
bool async_grab_camera_recovery (self)
 Define the behavior of the automatic camera recovery during sl.Camera.grab() method call. More...
 
float grab_compute_capping_fps (self)
 Define a computation upper limit to the grab frequency. More...
 
bool enable_image_validity_check (self)
 Enable or disable the image validity verification. More...
 
None set_from_camera_id (self, uint id, BUS_TYPE bus_type=BUS_TYPE.AUTO)
 Defines the input source with a camera id to initialize and open an sl.Camera object from. More...
 
None set_from_serial_number (self, uint serial_number, BUS_TYPE bus_type=BUS_TYPE.AUTO)
 Defines the input source with a serial number to initialize and open an sl.Camera object from. More...
 
None set_from_svo_file (self, str svo_input_filename)
 Defines the input source with an SVO file to initialize and open an sl.Camera object from. More...
 
None set_from_stream (self, str sender_ip, port=30000)
 Defines the input source from a stream to initialize and open an sl.Camera object from. 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.

import pyzed.sl as sl
def main() :
zed = sl.Camera() # Create a ZED camera object
init_params = sl.InitParameters() # Set initial parameters
init_params.sdk_verbose = 0 # Disable verbose mode
# Use the camera in LIVE mode
init_params.camera_resolution = sl.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.set_from_svo_file("xxxx.svo")
# Or use the camera in STREAM mode
#init_params.set_from_stream("192.168.1.12", 30000)
# Other parameters are left to their default values
# Open the camera
err = zed.open(init_params)
if err != sl.ERROR_CODE.SUCCESS:
exit(-1)
# Close the camera
zed.close()
return 0
if __name__ == "__main__" :
main()
Definition: sl.pyx:1

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.

Functions

◆ __cinit__()

InitParameters __cinit__ (   self,
  camera_resolution = RESOLUTION.AUTO,
  camera_fps = 0,
  svo_real_time_mode = False,
  depth_mode = DEPTH_MODE.PERFORMANCE,
  coordinate_units = UNIT.MILLIMETER,
  coordinate_system = COORDINATE_SYSTEM.IMAGE,
  sdk_verbose = 1,
  sdk_gpu_id = -1,
  depth_minimum_distance = -1.0,
  depth_maximum_distance = -1.0,
  camera_disable_self_calib = False,
  camera_image_flip = FLIP_MODE.OFF,
  enable_right_side_measure = False,
  sdk_verbose_log_file = "",
  depth_stabilization = 1,
  input_t = InputType(),
  optional_settings_path = "",
  sensors_required = False,
  enable_image_enhancement = True,
  optional_opencv_calibration_file = "",
  open_timeout_sec = 5.0,
  async_grab_camera_recovery = False,
  grab_compute_capping_fps = 0,
  enable_image_validity_check = False 
)

Default constructor.

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

Parameters
camera_resolution: Chosen camera_resolution
camera_fps: Chosen camera_fps
svo_real_time_mode: Activates svo_real_time_mode
depth_mode: Chosen depth_mode
coordinate_units: Chosen coordinate_units
coordinate_system: Chosen coordinate_system
sdk_verbose: Sets sdk_verbose
sdk_gpu_id: Chosen sdk_gpu_id
depth_minimum_distance: Chosen depth_minimum_distance
depth_maximum_distance: Chosen depth_maximum_distance
camera_disable_self_calib: Activates camera_disable_self_calib
camera_image_flip: Sets camera_image_flip
enable_right_side_measure: Activates enable_right_side_measure
sdk_verbose_log_file: Chosen sdk_verbose_log_file
depth_stabilization: Activates depth_stabilization
input_t: Chosen input_t (InputType )
optional_settings_path: Chosen optional_settings_path
sensors_required: Activates sensors_required
enable_image_enhancement: Activates enable_image_enhancement
optional_opencv_calibration_file: Sets optional_opencv_calibration_file
open_timeout_sec: Sets open_timeout_sec
async_grab_camera_recovery: Sets async_grab_camera_recovery
grab_compute_capping_fps: Sets grab_compute_capping_fps
params = sl.InitParameters(camera_resolution=sl.RESOLUTION.HD720, camera_fps=30, depth_mode=sl.DEPTH_MODE.PERFORMANCE)

◆ save()

bool save (   self,
str  filename 
)

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
init_params = sl.InitParameters() # Set initial parameters
init_params.sdk_verbose = 1 # Enable verbose mode
init_params.set_from_svo_file("/path/to/file.svo") # Selects the and SVO file to be read
init_params.save("initParameters.conf") # Export the parameters into a file

◆ load()

bool load (   self,
str  filename 
)

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.
init_params = sl.InitParameters() # Set initial parameters
init_params.load("initParameters.conf") # Load the init_params from a previously exported file

◆ camera_resolution()

RESOLUTION camera_resolution (   self)

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

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.

Referenced by CameraConfiguration.fps().

◆ sensors_required()

bool sensors_required (   self)

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

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.

◆ svo_real_time_mode()

bool svo_real_time_mode (   self)

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

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.

◆ coordinate_units()

UNIT coordinate_units (   self)

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

Default: sl.UNIT.MILLIMETER

◆ coordinate_system()

COORDINATE_SYSTEM coordinate_system (   self)

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

int sdk_verbose (   self)

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: 0 (no verbose message)

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

◆ sdk_gpu_id()

int sdk_gpu_id (   self)

NVIDIA graphics card id 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.

◆ depth_minimum_distance()

float depth_minimum_distance (   self)

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

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

◆ camera_disable_self_calib()

bool camera_disable_self_calib (   self)

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.update_self_calibration(), even if this parameter is set to true.

◆ camera_image_flip()

FLIP_MODE camera_image_flip (   self)

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.

◆ enable_right_side_measure()

bool enable_right_side_measure (   self)

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

◆ sdk_verbose_log_file()

str sdk_verbose_log_file (   self)

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.
Warning
The log file won't be cleared after successive executions of the application.
This means that it can grow indefinitely if not cleared.

◆ depth_stabilization()

int depth_stabilization (   self)

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.enable_positional_tracking() with your own parameters afterwards is still possible.

◆ optional_settings_path()

str optional_settings_path (   self)

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.
init_params = sl.InitParameters() # Set initial parameters
home = "/path/to/home"
path = home + "/Documents/settings/" # assuming /path/to/home/Documents/settings/SNXXXX.conf exists. Otherwise, it will be searched in /usr/local/zed/settings/
init_params.optional_settings_path = path

◆ optional_opencv_calibration_file()

str optional_opencv_calibration_file (   self)

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

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

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

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.

◆ enable_image_validity_check()

bool enable_image_validity_check (   self)

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)

◆ set_from_camera_id()

None set_from_camera_id (   self,
uint  id,
BUS_TYPE   bus_type = BUS_TYPE.AUTO 
)

Defines the input source with a camera id to initialize and open an sl.Camera object from.

Parameters
id: Id of the desired camera to open.
bus_type: sl.BUS_TYPE of the desired camera to open.

◆ set_from_serial_number()

None set_from_serial_number (   self,
uint  serial_number,
BUS_TYPE   bus_type = BUS_TYPE.AUTO 
)

Defines the input source with a serial number to initialize and open an sl.Camera object from.

Parameters
serial_number: Serial number of the desired camera to open.
bus_type: sl.BUS_TYPE of the desired camera to open.

◆ set_from_svo_file()

None set_from_svo_file (   self,
str  svo_input_filename 
)

Defines the input source with an SVO file to initialize and open an sl.Camera object from.

Parameters
svo_input_filename: Path to the desired SVO file to open.

◆ set_from_stream()

None set_from_stream (   self,
str  sender_ip,
  port = 30000 
)

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

Parameters
sender_ip: IP address of the streaming sender.
port: Port on which to listen. Default: 30000