Show EOL distros: 

freenect_stack: freenect_camera | freenect_launch | libfreenect

Package Summary

A libfreenect based ROS driver for the Microsoft Kinect. This is a port of the OpenNI driver to use libfreenect.

freenect_stack

Package Summary

A libfreenect based ROS driver for the Microsoft Kinect. This is a port of the OpenNI driver to use libfreenect.

Package Summary

A libfreenect-based ROS driver for the Microsoft Kinect. This is a port of the OpenNI driver that uses libfreenect instead, because on some systems with some devices it works better.

Package Summary

A libfreenect-based ROS driver for the Microsoft Kinect. This is a port of the OpenNI driver that uses libfreenect instead, because on some systems with some devices it works better.

Package Summary

A libfreenect-based ROS driver for the Microsoft Kinect. This is a port of the OpenNI driver that uses libfreenect instead, because on some systems with some devices it works better.

Package Summary

A libfreenect-based ROS driver for the Microsoft Kinect. This is a port of the OpenNI driver that uses libfreenect instead, because on some systems with some devices it works better.

New in Fuerte

Overview

This package provides a ROS interface to the Microsoft Kinect using the libfreenect library from OpenKinect. Other devices using the OpenNI standard are currently not supported. Please see the section on other OpenNI devices for more information:

freenect_launch contains some convenience scripts that can be used to run this driver.

The goal of this libfreenect based driver is to provide a substitute to the OpenNI based ROS driver (openni_camera). Migration is easy and documented below.

Dev Mailing List: ros-freenect-dev@googlegroups.com

ROS API

The ROS API is extremely similar to that of openni_camera. Any differences are described in the API and the migration guide.

freenect_node

libfreenect 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 (device 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 (device 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
Published by the driver only when no subscriptions to the rgb image exist.
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.
[new in freenect_camera] Diagnostics
/diagnostics (diagnostic_msgs/DiagnosticArray)
  • Simple topic frequency diagnostics for RGB, Depth and IR images. Only published if enabled through parameters described below.

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)
  • [different in freenect_camera] Specifies which device to open. The following formats are recognized:
    • #1 Use first device found
      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 the device and distortion unmodeled.
~time_out (double)
  • If set, checks every ~time_out seconds whether active cameras have streamed new data.
~debug (bool, default: false)
  • [new in freenect_camera] If set, enables verbose libfreenect output useful for debugging errors.
[new in freenect_camera] Diagnostics Parameters
enable_rgb_diagnostics (bool, default: false)
  • If set, enables simple frequency based topic diagnostics on RGB Image publication (rgb/image_raw) that can be viewed through robot_monitor.
enable_ir_diagnostics (bool, default: false)
  • If set, enables simple frequency based topic diagnostics on IR Image publication (ir/image_raw) that can be viewed through robot_monitor.
enable_depth_diagnostics (bool, default: false)
  • If set, enables simple frequency based topic diagnostics on Depth Image publication (depth/image_raw OR depth_registered/image_raw) that can be viewed through robot_monitor.
diagnostics_max_frequency (double, default: 30.0)
  • The maximum frequency expected by diagnostics for any enabled topic (in hz).
diagnostics_min_frequency (double, default: 30.0)
  • The minimum frequency expected by diagnostics for any enabled topic (in hz).
diagnostics_tolerance (double, default: 0.05)
  • The amount beyond min/max where diagnostics won't generate a warning. For the default values. this means a frequency between 28.5 and 31.5 hz.
diagnostics_window_time (double, default: 5.0)
  • The duration of the window that diagnostics uses to monitor a topic (in seconds).
Dynamically Reconfigurable Parameters
See the dynamic_reconfigure package for details on dynamically reconfigurable parameters.
~image_mode (int, default: 2)
  • [different in freenect_camera] Image output mode Possible values are: SXGA (1): 1280x1024, VGA (2): 640x480. SXGA should be considered unstable
~depth_mode (int, default: 2)
  • [different in freenect_camera] Depth output mode Possible values are: SXGA (1): 1280x1024, VGA (2): 640x480. SXGA is not supported for depth mode
~depth_registration (bool, default: True)
  • 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

freenect_camera/driver nodelet

Nodelet version of the freenect driver. Has the same ROS API as freenect_node above.

Migration guide

This guide assumes that you are using the freenect_launch package to launch the driver. If not, migration is non-trivial but not overly difficult, and can be done by studying the differences between freenect_launch and openni_launch.

Migrating to openni_camera

  1. Replace the freenect launch file in your code with the corresponding openni launch file. ($(find freenect_launch)/launch/freenect.launch -> $(find openni_launch)/launch/openni.launch). No other modifications should be necessary.

  2. openni_launch does not support diagnostics or appending a namespace as of v1.8.3. Modify your system accordingly. Note: A ticket for ns addition to openni_launch has been filed #63 #64

Migrating from openni_camera

  1. Replace the openni launch file in your code with the corresponding freenect launch file. ($(find openni_launch)/launch/openni.launch -> $(find freenect_launch)/launch/freenect.launch).

  2. If you were using the default image_mode or depth_mode parameters in the openni_camera driver, then please skip this step. freenect_camera does not support a number of image/depth modes supported by the openni_camera driver. Please use one of modes mentioned in the parameters above (SXGA equivalent to SXGA_15Hz), or (VGA equivalent to VGA_30Hz). SXGA should be considered unstable.

  3. If you were using the bus/address method of searching for the device, then it is no longer supported. Please consult the parameters above on other methods of selecting devices.

Other OpenNI devices

There are a couple of reasons why other devices using the OpenNI standard (namely the Primesense PSDK, Asus Xtion Pro and Pro Live) are not currently supported:

  1. libfreenect hardcodes information about the Kinect in a way that makes it difficult to gain access to different types of OpenNI devices using the same code. It might be easy to patch libfreenect to use these other devices, generate separate libraries for each device, and make multiple binaries of the driver linking against each library separately.

  2. Information about each device will have to be reverse engineered from the OpenNI driver to modify libfreenect. A port for the Asus Xtion Pro is available here (thanks for pointing to this Ivan!). A read through the differences reveal that the changes are not big, but require knowledge about the commands that need to be passed to each device using libusb. It is currently not clear how easy this task is.

Wiki: freenect_camera (last edited 2013-06-26 20:26:17 by PiyushKhandelwal)