Video3D

class quanser.multimedia.video.Video3D(device_id=None)

A Python wrapper for the Quanser Media 3D API.

Parameters

device_id (string) – The device identifier. If device_id is a number, such as “3”, then it will open the device based on its index in the device list. The number may be octal or hexadecimal as well. Otherwise, it will identify the device by serial number.

Raises

MediaError – On non-zero return code. A suitable error message may be retrieved using get_error_message.

Examples

Constructs a new Video3D object without opening a connection to a device.

>>> from quanser.multimedia import Video3D
>>> video3d = Video3D()
>>> # ...
...
>>> video3d.close()

Constructs a new Video3D object and opens a connection to the specified video3d device.

>>> from quanser.multimedia import Video3D
>>> video3d = Video3D("0")
>>> # ...
...
>>> video3d.close()
close()

Closes a video3d device.

Raises

MediaError – On non-zero return code. A suitable error message may be retrieved using get_error_message.

Example

>>> from quanser.multimedia import Video3D
>>> video3d = Video3D()
>>> video3d.open("0")
>>> # ...
...
>>> video3d.close()
open(device_id)

Opens a video3d device.

Parameters

device_id (string) – The device identifier. If device_id is a number, such as “3”, then it will open the device based on its index in the device list. The number may be octal or hexadecimal as well. Otherwise, it will identify the device by serial number.

Raises

MediaError – On non-zero return code. A suitable error message may be retrieved using get_error_message.

Example

Opens the specified video3d device.

>>> from quanser.multimedia import Video3D
>>> video3d = Video3D()
>>> video3d.open("0")
>>> # ...
...
>>> video3d.close()
open_file(device_file)

Opens a video3d file to emulate a device.

Parameters

device_file (string) – The path to the video3d file.

Raises

MediaError – On non-zero return code. A suitable error message may be retrieved using get_error_message.

Example

>>> from os import path
>>> from quanser.multimedia import Video3D
>>> file_path = path.join("path", "to", "ros.bag")
>>> video3d = Video3D()
>>> video3d.open_file(file_path)
>>> # ...
...
>>> video3d.close()
start_streaming()

Starts streaming on all open streams.

Raises

MediaError – On non-zero return code. A suitable error message may be retrieved using get_error_message.

Example

Starts streaming the depth and color streams, both at 1280x720 @30fps, on a live camera.

>>> from quanser.multimedia import Video3D, ImageDataType, ImageFormat, Video3DStreamType
>>> stream_index = 0
>>> frame_width = 1280
>>> frame_height = 720
>>> frame_rate = 30.0
>>> video3d = Video3D("0")
>>> depth_stream = video3d.stream_open(Video3DStreamType.DEPTH, stream_index,
...                                    frame_rate, frame_width, frame_height,
...                                    ImageFormat.ROW_MAJOR_GREYSCALE, ImageDataType.UINT16)
...
>>> color_stream = video3d.stream_open(Video3DStreamType.COLOR, stream_index,
...                                    frame_rate, frame_width, frame_height,
...                                    ImageFormat.ROW_MAJOR_INTERLEAVED_BGR, ImageDataType.UINT8)
...
>>> video3d.start_streaming()
>>> # ...
...
>>> video3d.stop_streaming()
>>> depth_stream.close()
>>> color_stream.close()
>>> video3d.close()
stop_streaming()

Stops streaming on all open streams.

Raises

MediaError – On non-zero return code. A suitable error message may be retrieved using get_error_message.

Example

Stops streaming the depth and color streams on a live camera.

>>> from quanser.multimedia import Video3D, ImageDataType, ImageFormat
>>> stream_index = 0
>>> frame_width = 1280
>>> frame_height = 720
>>> frame_rate = 30.0
>>> video3d = Video3D("0")
>>> depth_stream = video3d.stream_open(Video3DStreamType.DEPTH, stream_index,
...                                    frame_rate, frame_width, frame_height,
...                                    ImageFormat.ROW_MAJOR_GREYSCALE, ImageDataType.UINT16)
...
>>> color_stream = video3d.stream_open(Video3DStreamType.COLOR, stream_index,
...                                    frame_rate, frame_width, frame_height,
...                                    ImageFormat.ROW_MAJOR_INTERLEAVED_BGR, ImageDataType.UINT8)
...
>>> video3d.start_streaming()
>>> # ...
...
>>> video3d.stop_streaming()
>>> depth_stream.close()
>>> color_stream.close()
>>> video3d.close()
stream_open(stream_type, index, frame_rate, frame_width, frame_height, image_format, image_data_type)

Enables a video3d stream.

This function looks for an exact match for the stream type, frame width, and frame height, but is more lenient with regards to the frame rate, finding the closest rate.

Parameters
  • stream_type (Video3DStreamType) – The type of image data to be enabled (e.g. depth, infrared, color, etc.)

  • index (int) – The zero-based index of the stream.

  • frame_rate (float) – The frame rate in Hz.

  • frame_width (int) – The frame width.

  • frame_height (int) – The frame height.

  • image_format (ImageFormat) –

    The format argument describes the format for the image frames retrieved.

    If the image format is ImageFormat.ROW_MAJOR_INTERLEAVED_BGR, then the data is stored in CV_8UC3 format, which is a row-major interleaved format. In other words, the BGR components of each pixel are stored contiguously, with one byte per colour component, and pixels are stored row by row. The data type must be ImageDataType.UINT8 in this case.

    If the image format is ImageFormat.ROW_MAJOR_GREYSCALE, then the data is stored in CV_8UC1 format, which is a row-major format. In other words, there is one byte per pixel, and pixels are stored row by row. The data type must be ImageDataType.UINT8 in this case.

    If the image format is ImageFormat.COL_MAJOR_PLANAR_RGB, then the data is stored in a column-major planar format. In other words, pixels are stored column by column, with all the red components stored together, followed by all the green components, and finally, all the blue components.

    If the image format is ImageFormat.COL_MAJOR_GREYSCALE, then the data is stored in column-major format. In other words, there is one byte per pixel, and pixels are stored column by column.

  • image_data_type (ImageDataType) – The image data type.

Raises

MediaError – On non-zero return code. A suitable error message may be retrieved using get_error_message.

Example

Open a color stream on a live camera.

>>> from quanser.multimedia import Video3D, ImageDataType, ImageFormat, Video3DStreamType
>>> stream_index = 0
>>> frame_width = 1920
>>> frame_height = 1080
>>> frame_rate = 30.0
>>> video3d = Video3D("0")
>>> stream = video3d.stream_open(Video3DStreamType.COLOR, stream_index,
...                              frame_rate, frame_width, frame_height,
...                              ImageFormat.ROW_MAJOR_INTERLEAVED_BGR, ImageDataType.UINT8)
...
>>> # ...
...
>>> stream.close()
>>> video3d.close()

Open a depth stream on a live camera.

>>> from quanser.multimedia import Video3D, ImageDataType, ImageFormat, Video3DStreamType
>>> stream_index = 0
>>> frame_width = 1280
>>> frame_height = 720
>>> frame_rate = 30.0
>>> video3d = Video3D("0")
>>> stream = video3d.stream_open(Video3DStreamType.DEPTH, stream_index,
...                              frame_rate, frame_width, frame_height,
...                              ImageFormat.ROW_MAJOR_GREYSCALE, ImageDataType.UINT16)
...
>>> # ...
...
>>> stream.close()
>>> video3d.close()