Kinect Sensor

Interfaces for the Kinect 2 RGBD sesnor.

Kinect2Sensor

class perception.Kinect2Sensor(packet_pipeline_mode=1, registration_mode=1, depth_mode=0, device_num=0, frame=None)

Bases: perception.camera_sensor.CameraSensor

Class for interacting with a Kinect v2 RGBD sensor.

__init__(packet_pipeline_mode=1, registration_mode=1, depth_mode=0, device_num=0, frame=None)

Initialize a Kinect v2 sensor with the given configuration.

Parameters:
  • packet_pipeline_mode (int) – Either Kinect2PacketPipelineMode.OPENGL or Kinect2PacketPipelineMode.CPU – indicates packet processing type.
  • registration_mode (int) – Either Kinect2RegistrationMode.NONE or Kinect2RegistrationMode.COLOR_TO_DEPT – The mode for registering a color image to the IR camera frame of reference.
  • depth_mode (int) – Either Kinect2DepthMode.METERS or Kinect2DepthMode.MILLIMETERS – the units for depths returned from the Kinect frame arrays.
  • device_num (int) – The sensor’s device number on the USB bus.
  • frame (str) – The name of the frame of reference in which the sensor resides. If None, this will be set to ‘kinect2_num’, where num is replaced with the device number.
__del__()

Automatically stop the sensor for safety.

color_intrinsics

CameraIntrinsics – The camera intrinsics for the Kinect’s color camera.

ir_intrinsics

CameraIntrinsics – The camera intrinsics for the Kinect’s IR camera.

is_running

bool – True if the stream is running, or false otherwise.

frame

str – The reference frame of the sensor.

color_frame

str – The reference frame of the color sensor.

ir_frame

str – The reference frame of the IR sensor.

start()

Starts the Kinect v2 sensor stream.

Raises:IOError – If the Kinect v2 is not detected.
stop()

Stops the Kinect2 sensor stream.

Returns:True if the stream was stopped, False if the device was already stopped or was not otherwise available.
Return type:bool
frames(skip_registration=False)

Retrieve a new frame from the Kinect and convert it to a ColorImage, a DepthImage, and an IrImage.

Parameters:skip_registration (bool) – If True, the registration step is skipped.
Returns:The ColorImage, DepthImage, and IrImage of the current frame.
Return type:tuple of ColorImage, DepthImage, IrImage, numpy.ndarray
Raises:RuntimeError – If the Kinect stream is not running.
median_depth_img(num_img=1)

Collect a series of depth images and return the median of the set.

Parameters:num_img (int) – The number of consecutive frames to process.
Returns:The median DepthImage collected from the frames.
Return type:DepthImage

VirtualKinect2Sensor

class perception.VirtualKinect2Sensor(path_to_images, frame=None)

Bases: perception.camera_sensor.CameraSensor

Class for a virtual Kinect v2 sensor that uses pre-captured images stored to disk instead of actually connecting to a sensor. For debugging purposes.

__init__(path_to_images, frame=None)

Create a new virtualized Kinect v2 sensor.

This requires a directory containing a specific set of files.

First, the directory must contain a set of images, where each image has three files: - color_{#}.png - depth_{#}.npy - ir_{#}.npy In these, the {#} is replaced with the integer index for the image. These indices should start at zero and increase consecutively.

Second, the directory must contain CameraIntrisnics files for the color and ir cameras: - {frame}_color.intr - {frame}_ir.intr In these, the {frame} is replaced with the reference frame name that is passed as a parameter to this function.

Parameters:
  • path_to_images (str) – The path to a directory containing images that the virtualized sensor will return.
  • frame (str) – The name of the frame of reference in which the sensor resides. If None, this will be discovered from the files in the directory.
path_to_images

str – The path to a directory containing images that the virtualized sensor will return.

is_running

bool – True if the stream is running, or false otherwise.

frame

str – The reference frame of the sensor.

color_frame

str – The reference frame of the color sensor.

ir_frame

str – The reference frame of the IR sensor.

color_intrinsics

CameraIntrinsics – The camera intrinsics for the Kinect’s color camera.

ir_intrinsics

CameraIntrinsics – The camera intrinsics for the Kinect’s IR camera.

start()

Starts the Kinect v2 sensor stream.

In this virtualized sensor, this simply resets the image index to zero. Everytime start is called, we start the stream again at the first image.

stop()

Stops the Kinect2 sensor stream.

Returns:True if the stream was stopped, False if the device was already stopped or was not otherwise available.
Return type:bool
frames()

Retrieve the next frame from the image directory and convert it to a ColorImage, a DepthImage, and an IrImage.

Parameters:skip_registration (bool) – If True, the registration step is skipped.
Returns:The ColorImage, DepthImage, and IrImage of the current frame.
Return type:tuple of ColorImage, DepthImage, IrImage, numpy.ndarray
Raises:RuntimeError – If the Kinect stream is not running or if all images in the directory have been used.
median_depth_img(num_img=1)

Collect a series of depth images and return the median of the set.

Parameters:num_img (int) – The number of consecutive frames to process.
Returns:The median DepthImage collected from the frames.
Return type:DepthImage

Kinect2SensorFactory

class perception.Kinect2SensorFactory

Factory class for Kinect2 sensors.

static sensor(sensor_type, cfg)

Creates a Kinect2 sensor of the specified type.

Parameters:
  • sensor_type (str) – the type of the sensor (real or virtual)
  • cfg (YamlConfig) – dictionary of parameters for sensor initialization