Video3DStream
- class quanser.multimedia.video.Video3DStream(stream)
A python wrapper for a video3d stream. You should not need to create an instance of this class yourself.
- close()
Closes a stream.
- Raises
MediaError – On non-zero return code. A suitable error message may be retrieved using get_error_message.
Example
Close an open depth stream.
>>> from quanser.multimedia import Video3D, ImageDataType, ImageFormat >>> video3d = Video3D("0") >>> stream = video3d.stream_open(Video3DStreamType.DEPTH, 0, 30.0, 1280, 720, ... ImageFormat.ROW_MAJOR_GREYSCALE, ImageDataType.UINT8) ... >>> # ... ... >>> stream.close() >>> video3d.close()
- get_camera_intrinsics(intrinsics, coefficients)
Gets the camera intrinsics and the distortion model for the given stream.
- Parameters
intrinsics (array_like) – A (3,3) array to fill with the camera intrinsic matrix.
coefficients (array_like) – A 5-element array to fill with the distortion model coefficients.
- Raises
MediaError – On non-zero return code. A suitable error message may be retrieved using get_error_message.
Example
Get the camera intrinsics and distortion model for the depth stream.
>>> from quanser.multimedia import Video3D, ImageDataType, ImageFormat, Video3DStreamType, Video3DDistortionModel >>> video3d = Video3D("0") >>> stream = video3d.stream_open(Video3DStreamType.DEPTH, 0, 30.0, 1280, 720, ... ImageFormat.ROW_MAJOR_GREYSCALE, ImageDataType.UINT8) ... >>> intrinsics = np.zeros((3, 3), dtype=np.float32) >>> coefficients = np.zeros((5), dtype=np.float32) >>> model = stream.get_camera_intrinsics(intrinsics, coefficients) ... >>> video3d.stop_streaming() >>> stream.close() >>> video3d.close()
- get_depth_scale(data_type)
Gets the scale factor from depth expressed in the given data type to metres.
- Parameters
data_type (ImageDataType) – The data type of the depth image for which to get the scale factor to metres.
- Raises
MediaError – On non-zero return code. A suitable error message may be retrieved using get_error_message.
Example
Get the scale factor from a ImageDataType.UINT16 depth image to metres.
>>> from quanser.multimedia import Video3D, ImageDataType, ImageFormat, Video3DStreamType >>> video3d = Video3D("0") >>> depth_stream = video3d.stream_open(Video3DStreamType.DEPTH, 0, 30.0, 1280, 720, ... ImageFormat.ROW_MAJOR_GREYSCALE, ImageDataType.UINT16) ... >>> depth_scale = depth_stream.get_depth_scale(ImageDataType.UINT16) ... >>> video3d.stop_streaming() >>> depth_stream.close() >>> video3d.close()
- get_extrinsics(to_stream, extrinsics)
Gets the extrinsics transformation from this stream to the given stream.
- Parameters
extrinsics (array_like) – A (4,4) array to fill with the homogeneous transformation matrix representing the extrinsics.
- Raises
MediaError – On non-zero return code. A suitable error message may be retrieved using get_error_message.
Example
Get the extrinsics transform from the current stream to the given stream.
>>> from quanser.multimedia import Video3D, ImageDataType, ImageFormat, Video3DStreamType >>> video3d = Video3D("0") >>> depth_stream = video3d.stream_open(Video3DStreamType.DEPTH, 0, 30.0, 1280, 720, ... ImageFormat.ROW_MAJOR_GREYSCALE, ImageDataType.UINT8) >>> rgb_stream = video3d.stream_open(Video3DStreamType.COLOR, 0, 30.0, 1280, 720, ... ImageFormat.ROW_MAJOR_RGB, ImageDataType.UINT8) ... >>> extrinsics = np.zeros((4, 4), dtype=np.float32) >>> depth_stream.get_extrinsics(rgb_stream, extrinsics) ... >>> video3d.stop_streaming() >>> rgb_stream.close() >>> depth_stream.close() >>> video3d.close()
- get_frame()
Get the latest frame for the given stream. If no frame is available, then it raises
QERR_WOULD_BLOCK
. Only one frame may be retrieved at a time and the frame must be released before getting a new frame.- Raises
MediaError – On non-zero return code. A suitable error message may be retrieved using get_error_message.
Example
Capture and process 1000 frames from the depth stream.
>>> from quanser.multimedia import Video3D, ImageDataType, ImageFormat, Video3DStreamType >>> video3d = Video3D("0") >>> stream = video3d.stream_open(Video3DStreamType.DEPTH, 0, 30.0, 1280, 720, ... ImageFormat.ROW_MAJOR_GREYSCALE, ImageDataType.UINT8) ... >>> video3d.start_streaming() >>> for i in range(1000): ... frame = stream.get_frame() ... # Process... ... frame.release() ... >>> video3d.stop_streaming() >>> stream.close() >>> video3d.close()
- set_properties(properties, num_properties, values)
Sets the value of one or more properties of a stream. For boolean options, use a value of
0.0
or1.0
. All other options should have a range of0.0
to1.0
inclusive. The function will do the appropriate scaling for the internal camera settings. Any values outside the range will be saturated to lie within the range.- Parameters
properties (array_like) – An array of
Video3DProperty
to set.num_properties (int) – The number of properties in the properties array.
values (array_like) – An array of values. Each element in the values array corresponds to the same element in the properties array.
- Raises
MediaError – On non-zero return code. A suitable error message may be retrieved using get_error_message.
Example
Set the brightness to 100% and the contrast to 50% on a depth stream.
>>> import numpy as np >>> from quanser.multimedia import Video3D, ImageDataType, ImageFormat, Video3DProperty >>> video3d = Video3D("0") >>> stream = video3d.stream_open(Video3DStreamType.DEPTH, 0, 30.0, 1280, 720, ... ImageFormat.ROW_MAJOR_GREYSCALE, ImageDataType.UINT8) ... >>> properties = np.array([Video3DProperty.BRIGHTNESS, Video3DProperty.CONTRAST], dtype=np.int32) >>> num_properties = len(properties) >>> values = np.array([1.0, 0.5], dtype=np.float64) >>> stream.set_properties(properties, num_properties, values) >>> # ... ... >>> stream.close() >>> video3d.close()