Overview

This package provides a ROS interface to depth sensors using the OpenNI standard. These currently include:

  • Microsoft Kinect
  • ASUS Xtion PRO (no RGB)
  • ASUS Xtion PRO Live (with RGB)
  • PrimeSense PSDK 5.0

openni_devices.jpg

openni_launch is the best place to begin using your Kinect or similar device. It provides processed outputs such as point clouds.

As of Electric, openni_camera has been trimmed down to just the driver node(let) publishing the raw depth, IR and (if applicable) RGB images. As of Fuerte, it has been trimmed of some heavyweight dependencies (OpenCV, PCL) and made a unary stack to ease installing and running openni_camera on resource-constrained systems.

(If you are using the old, monolithic driver API dating to Diamondback, see openni_camera_deprecated for migration instructions and API reference.)

Installation

Ubuntu installation

To install only openni_camera:

sudo apt-get install ros-electric-openni-camera

It's also recommended to install openni_launch:

sudo apt-get install ros-electric-openni-launch

ROS API

openni_node

OpenNI camera driver.

Published Topics

RGB camera
rgb/camera_info (sensor_msgs/CameraInfo)
  • Camera calibration and metadata.
rgb/image_raw (sensor_msgs/Image)
  • Raw image from device. Format is Bayer GRBG for Kinect.
Depth camera
Published only when ~depth_registration is false (OpenNI registration disabled).
depth/camera_info (sensor_msgs/CameraInfo)
  • Camera calibration and metadata.
depth/image_raw (sensor_msgs/Image)
  • Raw image from device. Contains uint16 depths in mm.
Registered depth camera (aligned with RGB camera)
Published directly by driver only when ~depth_registration is true (OpenNI registration enabled).
depth_registered/camera_info (sensor_msgs/CameraInfo)
  • Camera calibration and metadata. Same as rgb/camera_info but time-synced to depth_registered/image_raw.
depth_registered/image_raw (sensor_msgs/Image)
  • Raw image from device. Contains uint16 depths in mm.
IR camera
ir/camera_info (sensor_msgs/CameraInfo)
  • Camera calibration and metadata.
ir/image_raw (sensor_msgs/Image)
  • Raw uint16 IR image.
IR projector
projector/camera_info (sensor_msgs/CameraInfo)
  • Faked calibration for the IR projector. Identical to depth/camera_info, but with the baseline encoded in the P matrix. Stereo processing nodes can use the depth and projector infos as a left/right pair.

Services

rgb/set_camera_info (sensor_msgs/SetCameraInfo)
  • Set the RGB camera calibration.
ir/set_camera_info (sensor_msgs/SetCameraInfo)
  • Set the IR camera calibration.

Parameters

~device_id (string, default: #1)
  • Specifies which device to open. The following formats are recognized:
    • #1 Use first device found
      2@3 Use device on USB bus 2, address 3
      B00367707227042B Use device with given serial number
~rgb_frame_id (string, default: /openni_rgb_optical_frame)
  • The tf frame of the RGB camera.
~depth_frame_id (string, default: /openni_depth_optical_frame)
  • The tf frame of the IR/depth camera.
~rgb_camera_info_url (string, default: file://${ROS_HOME}/camera_info/${NAME}.yaml)
  • Calibration URL for the RGB camera. By default, looks in your ROS home directory for calibration identified by the device serial number, e.g. $HOME/.ros/camera_info/rgb_B00367707227042B. If no calibration is found, uses a default camera model with a typical focal length and distortion unmodeled.
~depth_camera_info_url (string, default: file://${ROS_HOME}/camera_info/${NAME}.yaml)
  • Calibration URL for the IR/depth camera. By default, looks in your ROS home directory for calibration identified by the device serial number, e.g. $HOME/.ros/camera_info/depth_B00367707227042B. If no calibration is found, uses a default camera model with the focal length reported by OpenNI and distortion unmodeled.
~time_out (double)
  • If set, checks every ~time_out seconds whether active cameras have streamed new data.
Dynamically Reconfigurable Parameters
See the dynamic_reconfigure package for details on dynamically reconfigurable parameters.
~image_mode (int, default: 2)
  • Image output mode for the color/grayscale image Possible values are: SXGA_15Hz (1): 1280x1024@15Hz, VGA_30Hz (2): 640x480@30Hz, VGA_25Hz (3): 640x480@25Hz, QVGA_25Hz (4): 320x240@25Hz, QVGA_30Hz (5): 320x240@30Hz, QVGA_60Hz (6): 320x240@60Hz, QQVGA_25Hz (7): 160x120@25Hz, QQVGA_30Hz (8): 160x120@30Hz, QQVGA_60Hz (9): 160x120@60Hz
~depth_mode (int, default: 2)
  • depth output mode Possible values are: SXGA_15Hz (1): 1280x1024@15Hz, VGA_30Hz (2): 640x480@30Hz, VGA_25Hz (3): 640x480@25Hz, QVGA_25Hz (4): 320x240@25Hz, QVGA_30Hz (5): 320x240@30Hz, QVGA_60Hz (6): 320x240@60Hz, QQVGA_25Hz (7): 160x120@25Hz, QQVGA_30Hz (8): 160x120@30Hz, QQVGA_60Hz (9): 160x120@60Hz
~depth_registration (bool, default: False)
  • Depth data registration
~data_skip (int, default: 0)
  • Skip N images for every image published (rgb/depth/depth_registered/ir) Range: 0 to 10
~depth_time_offset (double, default: 0.0)
  • depth image time offset in seconds Range: -1.0 to 1.0
~image_time_offset (double, default: 0.0)
  • image time offset in seconds Range: -1.0 to 1.0
~depth_ir_offset_x (double, default: 5.0)
  • X offset between IR and depth images Range: -10.0 to 10.0
~depth_ir_offset_y (double, default: 4.0)
  • Y offset between IR and depth images Range: -10.0 to 10.0
~z_offset_mm (int, default: 0)
  • Z offset in mm Range: -50 to 50

openni_camera/driver nodelet

Nodelet version of the OpenNI driver. Has the same ROS API as openni_node above.

Wiki: openni_camera/electric (last edited 2012-08-08 21:17:42 by ChadRockey)