Class containing the options used to initialize the sl.Camera object. More...
Functions | |
InitParameters () | |
Default constructor. More... | |
Attributes | |
sl.INPUT_TYPE | inputType |
Defines the input source to initialize and open an sl.Camera object from. More... | |
sl.RESOLUTION | resolution |
Desired camera resolution. More... | |
int | cameraFPS |
Requested camera frame rate. More... | |
int | cameraDeviceID |
Id for identifying which camera to use from the connected cameras. More... | |
string | pathSVO = "" |
Path to a recorded SVO file to play, including filename. More... | |
bool | svoRealTimeMode |
Defines if sl.Camera object return the frame in real time mode. More... | |
UNIT | coordinateUnits |
Unit of spatial data (depth, point cloud, tracking, mesh, etc.) for retrieval. More... | |
COORDINATE_SYSTEM | coordinateSystem |
sl.COORDINATE_SYSTEM to be used as reference for positional tracking, mesh, point clouds, etc. More... | |
sl.DEPTH_MODE | depthMode |
sl.DEPTH_MODE to be used. More... | |
float | depthMinimumDistance |
Minimum depth distance to be returned, measured in the sl.UNIT defined in coordinateUnits. More... | |
float | depthMaximumDistance |
Maximum depth distance to be returned, measured in the sl.UNIT defined in coordinateUnits. More... | |
FLIP_MODE | cameraImageFlip |
Defines if a flip of the images is needed. More... | |
bool | enableRightSideMeasure |
Enable the measurement computation on the right images. More... | |
bool | cameraDisableSelfCalib |
Disables the self-calibration process at camera opening. More... | |
int | sdkVerbose |
Enable the ZED SDK verbose mode. More... | |
int | sdkGPUId |
NVIDIA graphics card id to use. More... | |
string | sdkVerboseLogFile = "" |
File path to store the ZED SDK logs (if sdkVerbose is enabled). More... | |
int | depthStabilization |
Defines whether the depth needs to be stabilized and to what extent. More... | |
string | optionalSettingsPath = "" |
Optional path where the ZED SDK has to search for the settings file (SNXXXX.conf file). More... | |
bool | sensorsRequired |
Requires the successful opening of the motion sensors before opening the camera. More... | |
string | ipStream = "" |
IP address of the streaming sender to connect to. More... | |
ushort | portStream = 30000 |
Port of the streaming sender to connect to. More... | |
bool | enableImageEnhancement = true |
Enable the Enhanced Contrast Technology, to improve image quality. More... | |
string | optionalOpencvCalibrationFile |
Optional path where the ZED SDK can find a file containing the calibration information of the camera computed by OpenCV. More... | |
float | openTimeoutSec |
Define a timeout in seconds after which an error is reported if the sl.Camera.Open() method fails. More... | |
bool | asyncGrabCameraRecovery |
Define the behavior of the automatic camera recovery during sl.Camera.Grab() method call. More... | |
float | grabComputeCappingFPS = 0 |
Define a computation upper limit to the grab frequency. More... | |
bool | enableImageValidityCheck |
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 grab function and requires some computations. If an issue is found, the grab function will output a warning as sl.ERROR_CODE.CORRUPTED_FRAME. This version doesn't detect frame tearing currently. default: disabled More... | |
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.
|
inline |
Default constructor.
All the parameters are set to their default and optimized values.
sl.INPUT_TYPE inputType |
Defines the input source to initialize and open an sl.Camera object from.
The SDK can handle different input types:
Default : (empty)
Referenced by InitParameters.InitParameters().
sl.RESOLUTION resolution |
Desired camera resolution.
Default:
Referenced by InitParameters.InitParameters().
int cameraFPS |
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.
int cameraDeviceID |
Id for identifying which camera to use from the connected cameras.
Referenced by Camera.GetInitParameters().
string pathSVO = "" |
Path to a recorded SVO file to play, including filename.
bool svoRealTimeMode |
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
UNIT coordinateUnits |
Unit of spatial data (depth, point cloud, tracking, mesh, etc.) for retrieval.
Default: sl.UNIT.MILLIMETER
COORDINATE_SYSTEM coordinateSystem |
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
sl.DEPTH_MODE depthMode |
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
Referenced by InitParameters.InitParameters().
float depthMinimumDistance |
Minimum depth distance to be returned, measured in the sl.UNIT defined in coordinateUnits.
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)
float depthMaximumDistance |
Maximum depth distance to be returned, measured in the sl.UNIT defined in coordinateUnits.
When estimating the depth, the ZED SDK uses this upper limit to turn higher values into inf ones.
FLIP_MODE cameraImageFlip |
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
bool enableRightSideMeasure |
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
bool cameraDisableSelfCalib |
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
int sdkVerbose |
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 (sdkVerbose >= 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)
int sdkGPUId |
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
string sdkVerboseLogFile = "" |
File path to store the ZED SDK logs (if sdkVerbose is enabled).
The file will be created if it does not exist.
Default: ""
int depthStabilization |
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]:
Default: 1
string optionalSettingsPath = "" |
Optional path where the ZED SDK has to search for the settings file (SNXXXX.conf file).
This file contains the calibration information of the camera.
Default: ""
bool sensorsRequired |
Requires the successful opening of the motion sensors before opening the camera.
Default: false.
This can be used for example when using a USB3.0 only extension cable (some fiber extension for example).
string ipStream = "" |
IP address of the streaming sender to connect to.
ushort portStream = 30000 |
Port of the streaming sender to connect to.
bool enableImageEnhancement = true |
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.
string optionalOpencvCalibrationFile |
Optional path where the ZED SDK can find a file containing the calibration information of the camera computed by OpenCV.
float openTimeoutSec |
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
bool asyncGrabCameraRecovery |
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 asyncGrabCameraRecovery 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
float grabComputeCappingFPS = 0 |
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.
This is an upper limit and won't make a difference if the computation is slower than the desired compute capping FPS.
bool enableImageValidityCheck |
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 grab function and requires some computations. If an issue is found, the grab function will output a warning as sl.ERROR_CODE.CORRUPTED_FRAME. This version doesn't detect frame tearing currently.
default: disabled