InputType Class Reference

Class defining the input type used in the ZED SDK. More...

Functions

None set_from_camera_id (self, uint, cam_id, BUS_TYPE bus_type=BUS_TYPE.AUTO)
 Set the input as the camera with specified id. More...
 
None set_from_serial_number (self, uint, serial_number)
 Set the input as the camera with specified serial number. More...
 
bool set_virtual_stereo_from_camera_id (self, uint, id_left, uint, id_right, uint, virtual_serial_number)
 Set the input as a virtual stereo camera from two cameras with specified ids. More...
 
bool set_virtual_stereo_from_serial_numbers (self, uint, camera_left_serial_number, uint, camera_right_serial_number, uint, virtual_serial_number)
 Set the input as a virtual stereo camera from two cameras with specified serial numbers. More...
 
None set_from_svo_file (self, str, svo_input_filename)
 Set the input as the svo specified with the filename. More...
 
None set_from_stream (self, str, sender_ip, int, port=30000)
 Set the input to stream with the specified ip and port. More...
 
INPUT_TYPE get_type (self)
 Returns the current input type.
 
str get_configuration (self)
 Returns the current input configuration as a string e.g: SVO name, serial number, streaming ip, etc.
 
bool is_init (self)
 Check whether the input is set.
 

Detailed Description

Class defining the input type used in the ZED SDK.

It can be used to select a specific camera with an id or serial number, or from a SVO file.

Functions

◆ set_from_camera_id()

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

Set the input as the camera with specified id.

Note
The id is not related to the serial number of the camera. The id is assigned by the OS depending on the order the cameras are plugged.
Warning
Using id is not recommended if you have multiple cameras plugged in the system, prefer using the serial number instead.
Parameters
id: Id of the camera to open. The default, -1, will open the first available camera. A number >= 0 will try to open the camera with the corresponding id.
bus_type: Whether the camera is a USB or a GMSL camera.

◆ set_from_serial_number()

None set_from_serial_number (   self,
  uint,
  serial_number 
)

Set the input as the camera with specified serial number.

Parameters
camera_serial_number: Serial number of the camera to open

◆ set_virtual_stereo_from_camera_id()

bool set_virtual_stereo_from_camera_id (   self,
  uint,
  id_left,
  uint,
  id_right,
  uint,
  virtual_serial_number 
)

Set the input as a virtual stereo camera from two cameras with specified ids.

Parameters
id_left: Id of the left camera.
id_right: Id of the right camera.
virtual_serial_number: Serial number of the virtual stereo camera.
Note
: The virtual serial number must fall within an interval that reflects the Product ID range.
This is necessary to avoid, for instance, downloading calibration data from an unrelated product.
The valid range is 110000000 to 119999999.
A support function can be used, based on the ZED One serial number, to compute a valid virtual serial number: generate_virtual_stereo_serial_number
Returns
False if there's no error and the camera was successfully created, otherwise True.

◆ set_virtual_stereo_from_serial_numbers()

bool set_virtual_stereo_from_serial_numbers (   self,
  uint,
  camera_left_serial_number,
  uint,
  camera_right_serial_number,
  uint,
  virtual_serial_number 
)

Set the input as a virtual stereo camera from two cameras with specified serial numbers.

Parameters
camera_left_serial_number: Serial number of the left camera.
camera_right_serial_number: Serial number of the right camera.
virtual_serial_number: Serial number of the virtual stereo camera.
Note
: The virtual serial number must fall within an interval that reflects the Product ID range.
This is necessary to avoid, for instance, downloading calibration data from an unrelated product.
The valid range is 110000000 to 119999999.
A support function can be used, based on the ZED One serial number, to compute a valid virtual serial number: generate_virtual_stereo_serial_number
Returns
False if there's no error and the camera was successfully created, otherwise True.

◆ set_from_svo_file()

None set_from_svo_file (   self,
  str,
  svo_input_filename 
)

Set the input as the svo specified with the filename.

Parameters
svo_input_filename: The path to the desired SVO file

◆ set_from_stream()

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

Set the input to stream with the specified ip and port.

Parameters
sender_ip: The IP address of the streaming sender
port: The port on which to listen. Default: 30000
Note
The protocol used for the streaming module is based on RTP/RTCP.
Warning
Port must be even number, since the port+1 is used for control data.