CameraOne Class Reference

This class serves as the primary interface between the camera and the various features provided by the SDK. More...

Functions

 CameraOne ()
 Default constructor. More...
 
 ~CameraOne ()
 Class destructor. More...
 
ERROR_CODE open (const InitParametersOne init_parameters=InitParametersOne())
 Opens the camera from the provided InitParametersOne. More...
 
bool isOpened ()
 Reports if the camera has been successfully opened. More...
 
InitParametersOne getInitParameters ()
 Returns the InitParameters used. More...
 
CameraOneInformation getCameraInformation (Resolution image_size=Resolution(0, 0))
 Returns the CameraOneInformation associated the camera being used. More...
 
ERROR_CODE close ()
 Close an opened camera. More...
 
float getCurrentFPS ()
 Returns the current framerate at which the grab() method is successfully called. More...
 
Timestamp getTimestamp (TIME_REFERENCE reference_time)
 Returns the timestamp in the requested TIME_REFERENCE. More...
 
ERROR_CODE grab ()
 This method will grab the latest images from the camera. This method is meant to be called frequently in the main loop of your application. More...
 
ERROR_CODE retrieveImage (Mat &oMat, VIEW view=VIEW::LEFT, sl::MEM mem=sl::MEM::CPU, Resolution image_size=sl::Resolution(0, 0))
 Retrieves images from the camera. More...
 
ERROR_CODE getSensorsData (SensorsData &oData, const TIME_REFERENCE reference_time)
 Retrieves the SensorsData (IMU) at a specific time reference. More...
 
ERROR_CODE getCameraSettings (VIDEO_SETTINGS settings, int &setting)
 Returns the current value of the requested camera setting (gain, brightness, hue, exposure, etc.). More...
 
ERROR_CODE getCameraSettings (VIDEO_SETTINGS settings, int &min_val, int &max_val)
 Fills the current values of the requested settings for VIDEO_SETTINGS that supports two values (min/max). More...
 
ERROR_CODE getCameraSettings (VIDEO_SETTINGS settings, Rect &roi)
 Overloaded method for VIDEO_SETTINGS::AEC_AGC_ROI which takes a Rect as parameter. More...
 
ERROR_CODE setCameraSettings (VIDEO_SETTINGS settings, int value=VIDEO_SETTINGS_VALUE_AUTO)
 Sets the value of the requested camera setting (gain, brightness, hue, exposure, etc.). More...
 
ERROR_CODE setCameraSettings (VIDEO_SETTINGS settings, int min, int max)
 Sets the value of the requested camera setting that supports two values (min/max). More...
 
ERROR_CODE setCameraSettings (VIDEO_SETTINGS settings, Rect roi, bool reset=false)
 Overloaded method for VIDEO_SETTINGS::AEC_AGC_ROI which takes a Rect as parameter. More...
 
ERROR_CODE getCameraSettingsRange (VIDEO_SETTINGS settings, int &min, int &max)
 Get the range for the specified camera settings VIDEO_SETTINGS as min/max value. More...
 
bool isCameraSettingSupported (VIDEO_SETTINGS setting)
 Test if the video setting is supported by the camera. More...
 
ERROR_CODE enableRecording (RecordingParameters recording_parameters)
 Creates an SVO file to be filled by enableRecording() and disableRecording(). More...
 
RecordingStatus getRecordingStatus ()
 Get the recording information. More...
 
void pauseRecording (bool status)
 Pauses or resumes the recording. More...
 
void disableRecording ()
 Disables the recording initiated by enableRecording() and closes the generated file. More...
 
unsigned int getFrameDroppedCount ()
 Returns the number of frames dropped since grab() was called for the first time. More...
 
int getSVOPosition ()
 Returns the current playback position in the SVO file. More...
 
int getSVOPositionAtTimestamp (const sl::Timestamp &timestamp)
 Retrieves the frame index within the SVO file corresponding to the provided timestamp. More...
 
void setSVOPosition (int frame_number)
 Sets the playback cursor to the desired frame number in the SVO file. More...
 
int getSVONumberOfFrames ()
 Returns the number of frames in the SVO file. More...
 
ERROR_CODE enableStreaming (StreamingParameters streaming_parameters=StreamingParameters())
 Creates a streaming pipeline. More...
 
void disableStreaming ()
 Disables the streaming initiated by enableStreaming(). More...
 
bool isStreamingEnabled ()
 Tells if the streaming is running. More...
 
StreamingParameters getStreamingParameters ()
 Returns the StreamingParameters used. More...
 

Static Functions

static ERROR_CODE reboot ()
 Performs a hardware reset of the CameraOne. More...
 
static std::vector< sl::DevicePropertiesgetDeviceList (void)
 List all the connected devices with their associated information. More...
 

Detailed Description

This class serves as the primary interface between the camera and the various features provided by the SDK.

Constructor and Destructor

◆ CameraOne()

CameraOne ( )

Default constructor.

Creates an empty CameraOne object. Its parameters will be set when calling open() with (optional) desired InitParametersOne.

◆ ~CameraOne()

~CameraOne ( )

Class destructor.

The destructor will call the close() function and clear the memory previously allocated by the object.

Functions

◆ open()

ERROR_CODE open ( const InitParametersOne  init_parameters = InitParametersOne())

Opens the camera from the provided InitParametersOne.

Parameters
init_parameters: A structure containing all the initial parameters. Default: a preset of InitParametersOne.
Returns
An error code giving information about the internal process. If ERROR_CODE::SUCCESS is returned, the camera is ready to use. Every other code indicates an error and the program should be stopped. Here is the proper way to call this function:
Note
If this method is called on an already opened camera, close() will be called.

◆ isOpened()

bool isOpened ( )

Reports if the camera has been successfully opened.

It has the same behavior as checking if open() returns ERROR_CODE::SUCCESS.

Returns
true if the camera is already setup, otherwise false.

◆ getInitParameters()

InitParametersOne getInitParameters ( )

Returns the InitParameters used.

It corresponds to the structure given as argument to the open() method.

Returns
InitParametersOne containing the parameters used to initialize the CameraOne object.

◆ getCameraInformation()

CameraOneInformation getCameraInformation ( Resolution  image_size = Resolution(0, 0))

Returns the CameraOneInformation associated the camera being used.

To ensure accurate calibration, it is possible to specify a custom resolution as a parameter when obtaining scaled information, as calibration parameters are resolution-dependent.
When reading an SVO file, the parameters will correspond to the camera used for recording.

Parameters
image_size: You can specify a size different from the default image size to get the scaled camera information. Default = (0,0) meaning original image size (given by getCameraInformation().camera_configuration.resolution).
Returns
CameraInformation containing the calibration parameters of the ZED, as well as serial number and firmware version.
Note
The CameraInformation.camera_configuration will contain two types of calibration parameters:
The calibration file SNXXXX.conf can be found in:
  • Windows: C:/ProgramData/Stereolabs/settings/
  • Linux: /usr/local/zed/settings/

◆ close()

ERROR_CODE close ( )

Close an opened camera.

If open() has been called, this method will close the connection to the camera (or the SVO file) and free the corresponding memory.

If open() wasn't called or failed, this method won't have any effects.

Note
To apply a new InitParameters, you will need to close the camera first and then open it again with the new InitParameters values.

◆ getCurrentFPS()

float getCurrentFPS ( )

Returns the current framerate at which the grab() method is successfully called.

The returned value is based on the difference of camera timestamps between two successful grab() calls.

Returns
The current SDK framerate.
Warning
The returned framerate (number of images grabbed per second) can be lower than InitParameters::camera_fps if the grab() function runs slower than the image stream or is called too often.

◆ getTimestamp()

Timestamp getTimestamp ( TIME_REFERENCE  reference_time)

Returns the timestamp in the requested TIME_REFERENCE.

  • When requesting the TIME_REFERENCE::IMAGE timestamp, the UNIX nanosecond timestamp of the latest grabbed image will be returned.
    This value corresponds to the time at which the entire image was available in the PC memory. As such, it ignores the communication time that corresponds to 1 or 2 frame-time based on the fps (ex: 16.6ms to 33ms at 60fps).
  • When requesting the TIME_REFERENCE::CURRENT timestamp, the current UNIX nanosecond timestamp is returned.


This function can also be used when playing back an SVO file.

Parameters
reference_time: The selected TIME_REFERENCE.
Returns
The timestamp in nanosecond. 0 if not available (SVO file without compression).
Note
As this function returns UNIX timestamps, the reference it uses is common across several CameraOne instances.
This can help to organized the grabbed images in a multi-camera application.

◆ grab()

ERROR_CODE grab ( )

This method will grab the latest images from the camera. This method is meant to be called frequently in the main loop of your application.

Note
If no new frames is available until timeout is reached, grab() will return ERROR_CODE::CAMERA_NOT_DETECTED since the camera has probably been disconnected.
Returns
ERROR_CODE::SUCCESS means that no problem was encountered.

◆ retrieveImage()

ERROR_CODE retrieveImage ( Mat oMat,
VIEW  view = VIEW::LEFT,
sl::MEM  mem = sl::MEM::CPU,
Resolution  image_size = sl::Resolution(0, 0) 
)

Retrieves images from the camera.

Warning
A sl::Mat resolution higher than the camera resolution cannot be requested.
Parameters
oMat: The sl::Mat to store the image. The method will create the Mat if necessary at the proper resolution. If already created, it will just update its data.
viewthe desired view, currently ZED X One only provide two view, VIEW::LEFT (lens distortion free) and VIEW::LEFT_UNRECTIFIED (with the lens distortion)
memthe desired memory type for your output image
image_size: If specified, define the resolution of the output sl::Mat. If set to Resolution(0,0), the camera resolution will be taken. Default: (0,0).
Returns
ERROR_CODE::SUCCESS if the method succeeded.
Note
As this method retrieves the images grabbed by the grab() method, it should be called afterward.

◆ getSensorsData()

ERROR_CODE getSensorsData ( SensorsData oData,
const TIME_REFERENCE  reference_time 
)

Retrieves the SensorsData (IMU) at a specific time reference.

The delta time between previous and current values can be calculated using data.imu.timestamp

Note
The IMU quaternion (fused data) is given in the specified COORDINATE_SYSTEM of InitParameters.
Parameters
data[out]: The SensorsData variable to store the data.
reference_frame[in]Defines the reference from which you want the data to be expressed. Default: REFERENCE_FRAME::WORLD.
Returns
ERROR_CODE::SUCCESS if sensors data have been extracted.

◆ getCameraSettings() [1/3]

ERROR_CODE getCameraSettings ( VIDEO_SETTINGS  settings,
int &  setting 
)

Returns the current value of the requested camera setting (gain, brightness, hue, exposure, etc.).

Possible values (range) of each setting are available here.

Parameters
settings: The requested setting.
setting: The setting variable to fill.
Returns
ERROR_CODE to indicate if the method was successful. If successful, setting will be filled with the corresponding value.
Note
The method works only if the camera is open in LIVE or STREAM mode.
Settings are not exported in the SVO file format.

◆ getCameraSettings() [2/3]

ERROR_CODE getCameraSettings ( VIDEO_SETTINGS  settings,
int &  min_val,
int &  max_val 
)

Fills the current values of the requested settings for VIDEO_SETTINGS that supports two values (min/max).

This method only works with the following VIDEO_SETTINGS:

Possible values (range) of each setting are available here.

Parameters
settings: The requested setting.
min_val: The setting minimum variable to fill.
max_val: The setting maximum variable to fill.
Returns
ERROR_CODE to indicate if the method was successful. If successful, setting will be filled with the corresponding value.

◆ getCameraSettings() [3/3]

ERROR_CODE getCameraSettings ( VIDEO_SETTINGS  settings,
Rect roi 
)

Overloaded method for VIDEO_SETTINGS::AEC_AGC_ROI which takes a Rect as parameter.

Parameters
setting: Must be set at VIDEO_SETTINGS::AEC_AGC_ROI, otherwise the method will have no impact.
roi: Roi that will be filled.
side: SIDE on which to get the ROI from.
Returns
ERROR_CODE to indicate if the method was successful. If successful, roi will be filled with the corresponding values.
Note
Works only if the camera is open in LIVE or STREAM mode with VIDEO_SETTINGS::AEC_AGC_ROI.
It will return ERROR_CODE::INVALID_FUNCTION_CALL or ERROR_CODE::INVALID_FUNCTION_PARAMETERS otherwise.

◆ setCameraSettings() [1/3]

ERROR_CODE setCameraSettings ( VIDEO_SETTINGS  settings,
int  value = VIDEO_SETTINGS_VALUE_AUTO 
)

Sets the value of the requested camera setting (gain, brightness, hue, exposure, etc.).

This method only applies for VIDEO_SETTINGS that require a single value.

Possible values (range) of each setting are available here.

Parameters
settings: The setting to be set.
value: The value to set. Default: auto mode
Returns
ERROR_CODE to indicate if the method was successful.
Warning
Setting VIDEO_SETTINGS::EXPOSURE or VIDEO_SETTINGS::GAIN to default will automatically sets the other to default.
Note
The method works only if the camera is open in LIVE or STREAM mode.

◆ setCameraSettings() [2/3]

ERROR_CODE setCameraSettings ( VIDEO_SETTINGS  settings,
int  min,
int  max 
)

Sets the value of the requested camera setting that supports two values (min/max).

This method only works with the following VIDEO_SETTINGS:

Possible values (range) of each setting are available here.

Parameters
settings: The setting to be set.
min: The minimum value that can be reached (-1 or 0 gives full range).
max: The maximum value that can be reached (-1 or 0 gives full range).
Returns
ERROR_CODE to indicate if the method was successful.
Warning
If VIDEO_SETTINGS settings is not supported or min >= max, it will return ERROR_CODE::INVALID_FUNCTION_PARAMETERS.
Note
The method works only if the camera is open in LIVE or STREAM mode.

◆ setCameraSettings() [3/3]

ERROR_CODE setCameraSettings ( VIDEO_SETTINGS  settings,
Rect  roi,
bool  reset = false 
)

Overloaded method for VIDEO_SETTINGS::AEC_AGC_ROI which takes a Rect as parameter.

Parameters
setting: Must be set at VIDEO_SETTINGS::AEC_AGC_ROI, otherwise the method will have no impact.
roi: Rect that defines the target to be applied for AEC/AGC computation. Must be given according to camera resolution.
side: SIDE on which to be applied for AEC/AGC computation.
reset: Cancel the manual ROI and reset it to the full image.
Note
Works only if the camera is open in LIVE or STREAM mode with VIDEO_SETTINGS::AEC_AGC_ROI.
Returns
ERROR_CODE to indicate if the method was successful.

◆ getCameraSettingsRange()

ERROR_CODE getCameraSettingsRange ( VIDEO_SETTINGS  settings,
int &  min,
int &  max 
)

Get the range for the specified camera settings VIDEO_SETTINGS as min/max value.

Parameters
setting: Must be set at a valid VIDEO_SETTINGS that accepts a min/max range and available for the current camera model.
Returns
ERROR_CODE to indicate if the method was successful.

◆ isCameraSettingSupported()

bool isCameraSettingSupported ( VIDEO_SETTINGS  setting)

Test if the video setting is supported by the camera.

Parameters
setting: The video setting to test
Returns
true if the VIDEO_SETTINGS is supported by the camera, false otherwise

◆ enableRecording()

ERROR_CODE enableRecording ( RecordingParameters  recording_parameters)

Creates an SVO file to be filled by enableRecording() and disableRecording().


SVO files are custom video files containing the un-rectified images from the camera along with some meta-data like timestamps or IMU orientation (if applicable).
They can be used to simulate a live ZED and test a sequence with various SDK parameters.
Depending on the application, various compression modes are available. See SVO_COMPRESSION_MODE.

Parameters
recording_parameters: A structure containing all the specific parameters for the recording such as filename and compression mode. Default: a reset of RecordingParameters .
Returns
An ERROR_CODE that defines if the SVO file was successfully created and can be filled with images.
Warning
This method can be called multiple times during a camera lifetime, but if video_filename is already existing, the file will be erased.

◆ getRecordingStatus()

RecordingStatus getRecordingStatus ( )

Get the recording information.

Returns
The recording state structure. For more details, see RecordingStatus.

◆ pauseRecording()

void pauseRecording ( bool  status)

Pauses or resumes the recording.

Parameters
status: If true, the recording is paused. If false, the recording is resumed.

◆ disableRecording()

void disableRecording ( )

Disables the recording initiated by enableRecording() and closes the generated file.

Note
This method will automatically be called by close() if enableRecording() was called.

◆ getFrameDroppedCount()

unsigned int getFrameDroppedCount ( )

Returns the number of frames dropped since grab() was called for the first time.

A dropped frame corresponds to a frame that never made it to the grab method.
This can happen if two frames were extracted from the camera when grab() is called. The older frame will be dropped so as to always use the latest (which minimizes latency).

Returns
The number of frames dropped since the first grab() call.

◆ getSVOPosition()

int getSVOPosition ( )

Returns the current playback position in the SVO file.

The position corresponds to the number of frames already read from the SVO file, starting from 0 to n.
Each grab() call increases this value by one (except when using InitParameters::svo_real_time_mode).

Returns
The current frame position in the SVO file. Returns -1 if the SDK is not reading an SVO.
Note
The method works only if the camera is open in SVO playback mode.
See also
setSVOPosition() for an example.

◆ getSVOPositionAtTimestamp()

int getSVOPositionAtTimestamp ( const sl::Timestamp &  timestamp)

Retrieves the frame index within the SVO file corresponding to the provided timestamp.

Parameters
timestampThe target timestamp for which the frame index is to be determined.
Returns
The frame index within the SVO file that aligns with the given timestamp. Returns -1 if the timestamp falls outside the bounds of the SVO file.

◆ setSVOPosition()

void setSVOPosition ( int  frame_number)

Sets the playback cursor to the desired frame number in the SVO file.

This method allows you to move around within a played-back SVO file. After calling, the next call to grab() will read the provided frame number.

Parameters
frame_number: The number of the desired frame to be decoded.
Note
The method works only if the camera is open in SVO playback mode.

◆ getSVONumberOfFrames()

int getSVONumberOfFrames ( )

Returns the number of frames in the SVO file.

Returns
The total number of frames in the SVO file. -1 if the SDK is not reading a SVO.
Note
The method works only if the camera is open in SVO playback mode.
See also
setSVOPosition() for an example.

◆ enableStreaming()

ERROR_CODE enableStreaming ( StreamingParameters  streaming_parameters = StreamingParameters())

Creates a streaming pipeline.

Parameters
streaming_parameters: A structure containing all the specific parameters for the streaming. Default: a reset of StreamingParameters .
Returns
ERROR_CODE::SUCCESS if streaming was successfully started.
ERROR_CODE::INVALID_FUNCTION_CALL if open() was not successfully called before.
ERROR_CODE::FAILURE if streaming RTSP protocol was not able to start.
ERROR_CODE::NO_GPU_COMPATIBLE if streaming codec is not supported (in this case, use H264 codec which is supported on all NVIDIA GPU the ZED SDK supports).

◆ disableStreaming()

void disableStreaming ( )

Disables the streaming initiated by enableStreaming().

Note
This method will automatically be called by close() if enableStreaming() was called.

See enableStreaming() for an example.

◆ isStreamingEnabled()

bool isStreamingEnabled ( )

Tells if the streaming is running.

Returns
true if the stream is running, false otherwise.

◆ getStreamingParameters()

StreamingParameters getStreamingParameters ( )

Returns the StreamingParameters used.

It corresponds to the structure given as argument to the enableStreaming() method.

Returns
StreamingParameters containing the parameters used for streaming initialization.

◆ reboot()

static ERROR_CODE reboot ( )
static

Performs a hardware reset of the CameraOne.

Returns
ERROR_CODE::SUCCESS if everything went fine.
ERROR_CODE::FAILURE otherwise.

◆ getDeviceList()

static std::vector<sl::DeviceProperties> getDeviceList ( void  )
static

List all the connected devices with their associated information.

This method lists all the cameras available and provides their serial number, models and other information.

Returns
The device properties for each connected camera.
Warning
As this method returns an std::vector, it is only safe to use in Release or ReleaseWithDebugInfos mode (not Debug).
This is due to a known compatibility issue between release (the SDK) and debug (your app) implementations of std::vector.