CameraOne Class Reference

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

Functions

None close (self)
 Close an opened camera. More...
 
ERROR_CODE open (self, InitParametersOne py_init=None)
 Opens the ZED camera from the provided InitParametersOne. More...
 
bool is_opened (self)
 Reports if the camera has been successfully opened. More...
 
ERROR_CODE grab (self)
 This method will grab the latest images from the camera, rectify them, and compute the measurements based on the RuntimeParameters provided (depth, point cloud, tracking, etc.) More...
 
ERROR_CODE retrieve_image (self, Mat, py_mat, view=VIEW.LEFT, mem_type=MEM.CPU, Resolution, resolution=None)
 Retrieves images from the camera (or SVO file). More...
 
def retrieve_tensor (self, Tensor, dest, TensorParameters, params)
 Retrieved a sl::Tensor, containing the input image pre-processed for inference with SVO or live camera. More...
 
def get_camera_settings_range (self, VIDEO_SETTINGS settings)
 Get the range for the specified camera settings VIDEO_SETTINGS as min/max value. More...
 
def get_svo_position_at_timestamp (self, Timestamp, timestamp)
 Retrieves the frame index within the SVO file corresponding to the provided timestamp. More...
 
ERROR_CODE set_svo_position (self, int, position)
 Sets the playback cursor to the desired position in the SVO file. More...
 
int get_svo_position (self)
 Returns the current playback position in the SVO file. More...
 
int get_svo_number_of_frames (self)
 Returns the number of frames in the SVO file. More...
 
ERROR_CODE ingest_data_into_svo (self, SVOData data)
 ingest a SVOData in the SVO file. More...
 
list get_svo_data_keys (self)
 Get the external channels that can be retrieved from the SVO file. More...
 
ERROR_CODE retrieve_svo_data (self, str key, dict data, Timestamp ts_begin, Timestamp ts_end)
 retrieve SVO datas from the SVO file at the given channel key and in the given timestamp range. More...
 
ERROR_CODE set_camera_settings (self, VIDEO_SETTINGS settings, value=-1)
 Sets the value of the requested camera setting (gain, brightness, hue, exposure, etc.). More...
 
ERROR_CODE set_camera_settings_range (self, VIDEO_SETTINGS settings, value_min=-1, value_max=-1)
 Sets the value of the requested camera setting that supports two values (min/max). More...
 
ERROR_CODE set_camera_settings_roi (self, VIDEO_SETTINGS settings, Rect roi, reset=False)
 Overloaded method for VIDEO_SETTINGS.AEC_AGC_ROI which takes a Rect as parameter. More...
 
tuple(ERROR_CODE, int) get_camera_settings (self, VIDEO_SETTINGS setting)
 Returns the current value of the requested camera setting (gain, brightness, hue, exposure, etc.). More...
 
tuple(ERROR_CODE, int, int) get_camera_settings_range (self, VIDEO_SETTINGS setting)
 Returns the values of the requested settings for VIDEO_SETTINGS that supports two values (min/max). More...
 
ERROR_CODE get_camera_settings_roi (self, VIDEO_SETTINGS setting, Rect roi)
 Returns the current value of the currently used ROI for the camera setting AEC_AGC_ROI. More...
 
bool is_camera_setting_supported (self, VIDEO_SETTINGS setting)
 Returns if the video setting is supported by the camera or not. More...
 
float get_current_fps (self)
 Returns the current framerate at which the grab() method is successfully called. More...
 
Timestamp get_timestamp (self, TIME_REFERENCE time_reference)
 Returns the timestamp in the requested TIME_REFERENCE. More...
 
int get_frame_dropped_count (self)
 Returns the number of frames dropped since grab() was called for the first time. More...
 
CameraOneInformation get_camera_information (self, resizer=None)
 Not implemented. More...
 
InitParametersOne get_init_parameters (self)
 Returns the InitParametersOne associated with the Camera object. More...
 
StreamingParameters get_streaming_parameters (self)
 Returns the StreamingParameters used. More...
 
ERROR_CODE get_sensors_data (self, SensorsData, py_sensor_data, time_reference=TIME_REFERENCE.CURRENT)
 Retrieves the SensorsData (IMU, magnetometer, barometer) at a specific time reference. More...
 
ERROR_CODE get_sensors_data_batch (self, list, py_sensor_data)
 Retrieves all SensorsData (IMU only) associated to most recent grabbed frame in the specified COORDINATE_SYSTEM of InitParameters. More...
 
ERROR_CODE enable_streaming (self, streaming_parameters=None)
 Creates a streaming pipeline. More...
 
None disable_streaming (self)
 Disables the streaming initiated by enable_streaming(). More...
 
bool is_streaming_enabled (self)
 Tells if the streaming is running. More...
 
ERROR_CODE enable_recording (self, RecordingParameters record)
 Creates an SVO file to be filled by enable_recording() and disable_recording(). More...
 
None disable_recording (self)
 Disables the recording initiated by enable_recording() and closes the generated file. More...
 
RecordingStatus get_recording_status (self)
 Get the recording information. More...
 
None pause_recording (self, value=True)
 Pauses or resumes the recording. More...
 

Static Functions

list[DevicePropertiesget_device_list ()
 List all the connected devices with their associated information. More...
 
list[StreamingPropertiesget_streaming_device_list ()
 Lists all the streaming devices with their associated information. More...
 
ERROR_CODE reboot (int sn, bool full_reboot=True)
 Performs a hardware reset of the ZED 2 and the ZED 2i. More...
 
ERROR_CODE reboot_from_input (INPUT_TYPE input_type)
 Performs a hardware reset of all devices matching the InputType. More...
 

Detailed Description

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

A standard program will use the Camera class like this:

import pyzed.sl as sl
def main():
# --- Initialize a Camera object and open the ZED
# Create a ZED camera object
zed = sl.CameraOne()
# Set configuration parameters
init_params = sl.InitParametersOne()
init_params.camera_resolution = sl.RESOLUTION.HD720 # Use HD720 video mode for USB cameras
# init_params.camera_resolution = sl.RESOLUTION.HD1200 # Use HD1200 video mode for GMSL cameras
init_params.camera_fps = 60 # Set fps at 60
# Open the camera
err = zed.open(init_params)
if err != sl.ERROR_CODE.SUCCESS:
print(repr(err))
exit(-1)
# --- Main loop grabbing images and depth values
# Capture 50 frames and stop
i = 0
image = sl.Mat()
depth = sl.Mat()
while i < 50 :
# Grab an image
if zed.grab() == sl.ERROR_CODE.SUCCESS: # A new image is available if grab() returns SUCCESS
# Display a pixel color
zed.retrieve_image(image, sl.VIEW.LEFT) # Get the left image
err, center_rgb = image.get_value(image.get_width() / 2, image.get_height() / 2)
if err == sl.ERROR_CODE.SUCCESS:
print("Image ", i, " center pixel R:", int(center_rgb[0]), " G:", int(center_rgb[1]), " B:", int(center_rgb[2]))
else:
print("Image ", i, " error:", err)
i = i+1
# --- Close the Camera
zed.close()
return 0
if __name__ == "__main__":
main()
Definition: sl.pyx:1

Functions

◆ close()

None close (   self)

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

Note
If an asynchronous task is running within the Camera object, like save_area_map(), this method will wait for its completion.
To apply a new InitParametersOne, you will need to close the camera first and then open it again with the new InitParameters values.
Warning
Therefore you need to make sure to delete your GPU sl.Mat objects before the context is destroyed.

◆ open()

ERROR_CODE open (   self,
InitParametersOne   py_init = None 
)

Opens the ZED camera from the provided InitParametersOne.

The method will also check the hardware requirements and run a self-calibration.

Parameters
py_init: 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:

zed = sl.CameraOne() # Create a ZED camera object
init_params = sl.InitParametersOne() # Set configuration parameters
init_params.camera_resolution = sl.RESOLUTION.HD720 # Use HD720 video mode
init_params.camera_fps = 60 # Set fps at 60
# Open the camera
err = zed.open(init_params)
if (err != sl.ERROR_CODE.SUCCESS) :
print(repr(err)) # Display the error
exit(-1)
Note
If you are having issues opening a camera, the diagnostic tool provided in the SDK can help you identify to problems.
  • Windows: C:\Program Files (x86)\ZED SDK\tools\ZED Diagnostic.exe
  • Linux: /usr/local/zed/tools/ZED Diagnostic
If this method is called on an already opened camera, close() will be called.

◆ is_opened()

bool is_opened (   self)

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 ZED camera is already setup, otherwise false.

◆ grab()

ERROR_CODE grab (   self)

This method will grab the latest images from the camera, rectify them, and compute the measurements based on the RuntimeParameters provided (depth, point cloud, tracking, etc.)

As measures are created in this method, its execution can last a few milliseconds, depending on your parameters and your hardware.
The exact duration will mostly depend on the following parameters:

This method is meant to be called frequently in the main loop of your application.

Note
Since ZED SDK 3.0, this method is blocking. It means that grab() will wait until a new frame is detected and available.
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.
Note
Returned errors can be displayed using str().
image = sl.Mat()
while True:
# Grab an image
if zed.grab() == sl.ERROR_CODE.SUCCESS: # A new image is available if grab() returns SUCCESS
zed.retrieve_image(image) # Get the left image
# Use the image for your application

◆ retrieve_image()

ERROR_CODE retrieve_image (   self,
  Mat,
  py_mat,
  view = VIEW.LEFT,
  mem_type = MEM.CPU,
  Resolution,
  resolution = None 
)

Retrieves images from the camera (or SVO file).

Multiple images are available along with a view of various measures for display purposes.
Available images and views are listed here.
As an example, VIEW.DEPTH can be used to get a gray-scale version of the depth map, but the actual depth values can be retrieved using retrieve_measure() .

Pixels
Most VIEW modes output image with 4 channels as BGRA (Blue, Green, Red, Alpha), for more information see enum VIEW

Memory
By default, images are copied from GPU memory to CPU memory (RAM) when this function is called.
If your application can use GPU images, using the type parameter can increase performance by avoiding this copy.
If the provided sl.Mat object is already allocated and matches the requested image format, memory won't be re-allocated.

Image size
By default, images are returned in the resolution provided by get_camera_information().camera_configuration.resolution.
However, you can request custom resolutions. For example, requesting a smaller image can help you speed up your application.

Warning
A sl.Mat resolution higher than the camera resolution cannot be requested.
Parameters
py_mat[out]: The sl.Mat to store the image.
view[in]: Defines the image you want (see VIEW). Default: VIEW.LEFT.
mem_type[in]: Defines on which memory the image should be allocated. Default: MEM.CPU (you cannot change this default value).
resolution[in]: If specified, defines 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.
ERROR_CODE.INVALID_FUNCTION_PARAMETERS if the view mode requires a module not enabled (VIEW.DEPTH with DEPTH_MODE.NONE for example).
ERROR_CODE.FAILURE if another error occurred.
Note
As this method retrieves the images grabbed by the grab() method, it should be called afterward.
# create sl.Mat objects to store the images
left_image = sl.Mat()
while True:
# Grab an image
if zed.grab() == sl.ERROR_CODE.SUCCESS: # A new image is available if grab() returns SUCCESS
zed.retrieve_image(left_image, sl.VIEW.LEFT) # Get the rectified left image
# Display the center pixel colors
err, left_center = left_image.get_value(left_image.get_width() / 2, left_image.get_height() / 2)
if err == sl.ERROR_CODE.SUCCESS:
print("left_image center pixel R:", int(left_center[0]), " G:", int(left_center[1]), " B:", int(left_center[2]))
else:
print("error:", err)

◆ retrieve_tensor()

def retrieve_tensor (   self,
  Tensor,
  dest,
  TensorParameters,
  params 
)

Retrieved a sl::Tensor, containing the input image pre-processed for inference with SVO or live camera.

This method provides a way to obtain the pre-processed input image in a format suitable for deep learning inference tasks. The retrieved Tensor is allocated on the GPU, allowing for efficient processing and integration with deep learning frameworks.

The pre-processing steps applied to the input image include resizing, normalization, and any other transformations required to prepare the image for inference.

This method is particularly useful when working with deep learning models that require specific input formats and pre-processing steps. By retrieving the pre-processed Tensor directly from the Camera class, users can streamline their workflow and ensure compatibility with their deep learning pipelines.

Note
This method requires that the camera has been opened in either LIVE mode, SVO mode or STREAM mode.
The retrieved Tensor is allocated on the GPU, so ensure that your system has sufficient GPU memory to accommodate the Tensor size.
Parameters
dest: The Tensor to store the pre-processed input image for inference.
params: Options to configure the pre-processing steps applied to the input image.
Returns
ERROR_CODE::SUCCESS if the method succeeded.
ERROR_CODE::INVALID_FUNCTION_PARAMETERS if the provided params are invalid.
ERROR_CODE::CAMERA_NOT_INITIALIZED if the camera is not opened.
ERROR_CODE::FAILURE if another error occurred.

◆ get_camera_settings_range() [1/2]

def get_camera_settings_range (   self,
VIDEO_SETTINGS  settings 
)

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

Parameters
settings: Must be set at a valid VIDEO_SETTINGS that accepts a min/max range and available for the current camera model.
min: The minimum value that can be reached to be fill.
max: The maximum value that can be reached to be fill.
Returns
ERROR_CODE to indicate if the method was successful.

Referenced by CameraOne.get_camera_settings_range().

◆ get_svo_position_at_timestamp()

def get_svo_position_at_timestamp (   self,
  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.

◆ set_svo_position()

ERROR_CODE set_svo_position (   self,
  int,
  position 
)

Sets the playback cursor to the desired position 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 position.

Parameters
position: The position in the SVO file.
Returns
An error code stating the success, or not.
Note
The method works only if the camera is open in SVO playback mode.
import pyzed.sl as sl
def main():
# Create a ZED camera object
zed = sl.CameraOne()
# Set configuration parameters
init_params = sl.InitParametersOne()
init_params.set_from_svo_file("path/to/my/file.svo")
# Open the camera
err = zed.open(init_params)
if err != sl.ERROR_CODE.SUCCESS:
print(repr(err))
exit(-1)
# Loop between frames 0 and 50
left_image = sl.Mat()
while zed.get_svo_position() < zed.get_svo_number_of_frames() - 1:
print("Current frame: ", zed.get_svo_position())
# Loop if we reached frame 50
if zed.get_svo_position() == 50:
err = zed.set_svo_position(0)
if err != sl.ERROR_CODE.SUCCESS:
print(repr(err))
exit(-1)
# Grab an image
if zed.grab() == sl.ERROR_CODE.SUCCESS:
zed.retrieve_image(left_image, sl.VIEW.LEFT) # Get the rectified left image
# Use the image in your application
# Close the Camera
zed.close()
return 0
if __name__ == "__main__" :
main()

◆ get_svo_position()

int get_svo_position (   self)

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 InitParametersOne.svo_real_time_mode).

Returns
The current frame position in the SVO file. -1 if the SDK is not reading an SVO.
Note
The method works only if the camera is open in SVO playback mode.

See set_svo_position() for an example.

◆ get_svo_number_of_frames()

int get_svo_number_of_frames (   self)

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.

The method works only if the camera is open in SVO playback mode.

◆ ingest_data_into_svo()

ERROR_CODE ingest_data_into_svo (   self,
SVOData  data 
)

ingest a SVOData in the SVO file.

Returns
An error code stating the success, or not.

The method works only if the camera is open in SVO recording mode.

◆ get_svo_data_keys()

list get_svo_data_keys (   self)

Get the external channels that can be retrieved from the SVO file.

Returns
a list of keys

The method works only if the camera is open in SVO playback mode.

◆ retrieve_svo_data()

ERROR_CODE retrieve_svo_data (   self,
str  key,
dict  data,
Timestamp  ts_begin,
Timestamp  ts_end 
)

retrieve SVO datas from the SVO file at the given channel key and in the given timestamp range.

Returns
An error code stating the success, or not.
Parameters
key: The channel key.
data: The dict to be filled with SVOData objects, with timestamps as keys.
ts_begin: The beginning of the range.
ts_end: The end of the range.

The method works only if the camera is open in SVO playback mode.

◆ set_camera_settings()

ERROR_CODE set_camera_settings (   self,
VIDEO_SETTINGS  settings,
  value = -1 
)

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 settings 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.
# Set the gain to 50
zed.set_camera_settings(sl.VIDEO_SETTINGS.GAIN, 50)

◆ set_camera_settings_range()

ERROR_CODE set_camera_settings_range (   self,
VIDEO_SETTINGS  settings,
  value_min = -1,
  value_max = -1 
)

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

This method only works with the following VIDEO_SETTINGS:

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.
# For ZED X based product, set the automatic exposure from 2ms to 5ms. Expected exposure time cannot go beyond those values
zed.set_camera_settings_range(sl.VIDEO_SETTINGS.AEC_RANGE, 2000, 5000);

◆ set_camera_settings_roi()

ERROR_CODE set_camera_settings_roi (   self,
VIDEO_SETTINGS  settings,
Rect  roi,
  reset = False 
)

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

Parameters
settings: 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.
reset: Cancel the manual ROI and reset it to the full image. Default: False
Note
The method works only if the camera is open in LIVE or STREAM mode.
roi = sl.Rect(42, 56, 120, 15)
zed.set_camera_settings_roi(sl.VIDEO_SETTINGS.AEC_AGC_ROI, roi)

◆ get_camera_settings()

tuple(ERROR_CODE, int) get_camera_settings (   self,
VIDEO_SETTINGS  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
setting: The requested setting.
Returns
ERROR_CODE to indicate if the method was successful.
The current value for the corresponding setting.
err, gain = zed.get_camera_settings(sl.VIDEO_SETTINGS.GAIN)
if err == sl.ERROR_CODE.SUCCESS:
print("Current gain value:", gain)
else:
print("error:", err)
Note
The method works only if the camera is open in LIVE or STREAM mode.
Settings are not exported in the SVO file format.

◆ get_camera_settings_range() [2/2]

tuple(ERROR_CODE, int, int) get_camera_settings_range (   self,
VIDEO_SETTINGS  setting 
)

Returns the 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
setting: The requested setting.
Returns
ERROR_CODE to indicate if the method was successful.
The current value of the minimum for the corresponding setting.
The current value of the maximum for the corresponding setting.
err, aec_range_min, aec_range_max = zed.get_camera_settings(sl.VIDEO_SETTINGS.AUTO_EXPOSURE_TIME_RANGE)
if err == sl.ERROR_CODE.SUCCESS:
print("Current AUTO_EXPOSURE_TIME_RANGE range values ==> min:", aec_range_min, "max:", aec_range_max)
else:
print("error:", err)
Note
Works only with ZED X that supports low-level controls

◆ get_camera_settings_roi()

ERROR_CODE get_camera_settings_roi (   self,
VIDEO_SETTINGS  setting,
Rect  roi 
)

Returns the current value of the currently used ROI for the camera setting AEC_AGC_ROI.

Parameters
setting[in]: Must be set at VIDEO_SETTINGS.AEC_AGC_ROI, otherwise the method will have no impact.
roi[out]: Roi that will be filled.
Returns
ERROR_CODE to indicate if the method was successful.
roi = sl.Rect()
err = zed.get_camera_settings_roi(sl.VIDEO_SETTINGS.AEC_AGC_ROI, roi)
print("Current ROI for AEC_AGC: " + str(roi.x) + " " + str(roi.y)+ " " + str(roi.width) + " " + str(roi.height))
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.

◆ is_camera_setting_supported()

bool is_camera_setting_supported (   self,
VIDEO_SETTINGS  setting 
)

Returns if the video setting is supported by the camera or not.

Parameters
setting[in]: the video setting to test
Returns
True if the VIDEO_SETTINGS is supported by the camera, False otherwise

◆ get_current_fps()

float get_current_fps (   self)

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 InitParametersOne.camera_fps if the grab() function runs slower than the image stream or is called too often.
current_fps = zed.get_current_fps()
print("Current framerate: ", current_fps)

◆ get_timestamp()

Timestamp get_timestamp (   self,
TIME_REFERENCE  time_reference 
)

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 2 or 3 frame-time based on the fps (ex: 33.3ms to 50ms 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
time_reference: 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 Camera instances.
This can help to organized the grabbed images in a multi-camera application.
last_image_timestamp = zed.get_timestamp(sl.TIME_REFERENCE.IMAGE)
current_timestamp = zed.get_timestamp(sl.TIME_REFERENCE.CURRENT)
print("Latest image timestamp: ", last_image_timestamp.get_nanoseconds(), "ns from Epoch.")
print("Current timestamp: ", current_timestamp.get_nanoseconds(), "ns from Epoch.")

◆ get_frame_dropped_count()

int get_frame_dropped_count (   self)

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.

◆ get_camera_information()

CameraOneInformation get_camera_information (   self,
  resizer = None 
)

Not implemented.

Returns the CameraInformation 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
resizer: 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 get_camera_information().camera_configuration.resolution).
Returns
CameraInformation containing the calibration parameters of the ZED, as well as serial number and firmware version.
Warning
The returned parameters might vary between two execution due to the self-calibration being run in the open() method.
Note
The calibration file SNXXXX.conf can be found in:
  • Windows: C:/ProgramData/Stereolabs/settings/
  • Linux: /usr/local/zed/settings/.

◆ get_init_parameters()

InitParametersOne get_init_parameters (   self)

Returns the InitParametersOne associated with the Camera object.

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

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

◆ get_streaming_parameters()

StreamingParameters get_streaming_parameters (   self)

Returns the StreamingParameters used.

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

Returns
StreamingParameters containing the parameters used for streaming initialization.

◆ get_sensors_data()

ERROR_CODE get_sensors_data (   self,
  SensorsData,
  py_sensor_data,
  time_reference = TIME_REFERENCE.CURRENT 
)

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

SensorsData object contains the previous IMUData structure that was used in ZED SDK v2.X:
For IMU data, the values are provided in 2 ways :

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 InitParametersOne.
Parameters
py_sensor_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.
ERROR_CODE.SENSORS_NOT_AVAILABLE if the camera model is a MODEL.ZED.
ERROR_CODE.MOTION_SENSORS_REQUIRED if the camera model is correct but the sensors module is not opened.
ERROR_CODE.INVALID_FUNCTION_PARAMETERS if the reference_time is not valid. See Warning.
Warning
In SVO reading mode, the TIME_REFERENCE.CURRENT is currently not available (yielding ERROR_CODE.INVALID_FUNCTION_PARAMETERS.
Only the quaternion data and barometer data (if available) at TIME_REFERENCE.IMAGE are available. Other values will be set to 0.

◆ get_sensors_data_batch()

ERROR_CODE get_sensors_data_batch (   self,
  list,
  py_sensor_data 
)

Retrieves all SensorsData (IMU only) associated to most recent grabbed frame in the specified COORDINATE_SYSTEM of InitParameters.

For IMU data, the values are provided in 2 ways:

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

Parameters
py_sensor_data[out]: The SensorsData list to store the data.
Returns
ERROR_CODE.SUCCESS if sensors data have been extracted.
ERROR_CODE.SENSORS_NOT_AVAILABLE if the camera model is a MODEL.ZED.
ERROR_CODE.MOTION_SENSORS_REQUIRED if the camera model is correct but the sensors module is not opened.
ERROR_CODE.INVALID_FUNCTION_PARAMETERS if the reference_time is not valid. See Warning.
if zed.grab() == sl.ERROR_CODE.SUCCESS:
sensors_data = []
if (zed.get_sensors_data_batch(sensors_data) == sl.ERROR_CODE.SUCCESS):
for data in sensors_data:
print("IMU data: ", data.imu.get_angular_velocity(), data.imu.get_linear_acceleration())
print("IMU pose: ", data.imu.get_pose().get_translation())
print("IMU orientation: ", data.imu.get_orientation().get())

◆ enable_streaming()

ERROR_CODE enable_streaming (   self,
  streaming_parameters = None 
)

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 the 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 the streaming codec is not supported (in this case, use H264 codec which is supported on all NVIDIA GPU the ZED SDK supports).
import pyzed.sl as sl
def main() :
# Create a ZED camera object
zed = sl.CameraOneOne()
# Set initial parameters
init_params = sl.InitParametersOne()
init_params.camera_resolution = sl.RESOLUTION.HD720 # Use HD720 video mode (default fps: 60)
# Open the camera
err = zed.open(init_params)
if err != sl.ERROR_CODE.SUCCESS :
print(repr(err))
exit(-1)
# Enable streaming
stream_params = sl.StreamingParameters()
stream_params.port = 30000
stream_params.bitrate = 8000
err = zed.enable_streaming(stream_params)
if err != sl.ERROR_CODE.SUCCESS :
print(repr(err))
exit(-1)
# Grab data during 500 frames
i = 0
while i < 500 :
if zed.grab() == sl.ERROR_CODE.SUCCESS :
i = i+1
zed.disable_streaming()
zed.close()
return 0
if __name__ == "__main__" :
main()

◆ disable_streaming()

None disable_streaming (   self)

Disables the streaming initiated by enable_streaming().

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

See enable_streaming() for an example.

◆ is_streaming_enabled()

bool is_streaming_enabled (   self)

Tells if the streaming is running.

Returns
True if the stream is running, False otherwise.

◆ enable_recording()

ERROR_CODE enable_recording (   self,
RecordingParameters  record 
)

Creates an SVO file to be filled by enable_recording() and disable_recording().


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
record: 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.
import pyzed.sl as sl
def main() :
# Create a ZED camera object
zed = sl.CameraOneOne()
# Set initial parameters
init_params = sl.InitParametersOne()
init_params.camera_resolution = sl.RESOLUTION.HD720 # Use HD720 video mode (default fps: 60)
init_params.coordinate_units = sl.UNIT.METER # Set units in meters
# Open the camera
err = zed.open(init_params)
if (err != sl.ERROR_CODE.SUCCESS):
print(repr(err))
exit(-1)
# Enable video recording
record_params = sl.RecordingParameters("myVideoFile.svo")
err = zed.enable_recording(record_params)
if (err != sl.ERROR_CODE.SUCCESS):
print(repr(err))
exit(-1)
# Grab data during 500 frames
i = 0
while i < 500 :
# Grab a new frame
if zed.grab() == sl.ERROR_CODE.SUCCESS:
# Record the grabbed frame in the video file
i = i + 1
zed.disable_recording()
print("Video has been saved ...")
zed.close()
return 0
if __name__ == "__main__" :
main()

◆ disable_recording()

None disable_recording (   self)

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

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

See enable_recording() for an example.

◆ get_recording_status()

RecordingStatus get_recording_status (   self)

Get the recording information.

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

◆ pause_recording()

None pause_recording (   self,
  value = True 
)

Pauses or resumes the recording.

Parameters
status: If True, the recording is paused. If False, the recording is resumed.

◆ get_device_list()

list[DeviceProperties] get_device_list ( )
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.

◆ get_streaming_device_list()

list[StreamingProperties] get_streaming_device_list ( )
static

Lists all the streaming devices with their associated information.

Returns
The streaming properties for each connected camera.
Warning
This method takes around 2 seconds to make sure all network informations has been captured. Make sure to run this method in a thread.

◆ reboot()

ERROR_CODE reboot ( int  sn,
bool   full_reboot = True 
)
static

Performs a hardware reset of the ZED 2 and the ZED 2i.

Parameters
sn: Serial number of the camera to reset, or 0 to reset the first camera detected.
full_reboot: Perform a full reboot (sensors and video modules) if True, otherwise only the video module will be rebooted.
Returns
ERROR_CODE::SUCCESS if everything went fine.
ERROR_CODE::CAMERA_NOT_DETECTED if no camera was detected.
ERROR_CODE::FAILURE otherwise.
Note
This method only works for ZED 2, ZED 2i, and newer camera models.
Warning
This method will invalidate any sl.Camera object, since the device is rebooting.

◆ reboot_from_input()

ERROR_CODE reboot_from_input ( INPUT_TYPE  input_type)
static

Performs a hardware reset of all devices matching the InputType.

Parameters
input_type: Input type of the devices to reset.
Returns
ERROR_CODE::SUCCESS if everything went fine.
ERROR_CODE::CAMERA_NOT_DETECTED if no camera was detected.
ERROR_CODE::FAILURE otherwise.
ERROR_CODE::INVALID_FUNCTION_PARAMETERS for SVOs and streams.
Warning
This method will invalidate any sl.Camera object, since the device is rebooting.