Show EOL distros: 

openni_kinect: depth_image_proc | nite | openni | openni_camera | openni_launch | openni_tracker

Package Summary

Launch files to open an OpenNI device and load all nodelets to convert raw depth/RGB/IR streams to depth images, disparity images, and (registered) point clouds.

openni_launch

Package Summary

Launch files to open an OpenNI device and load all nodelets to convert raw depth/RGB/IR streams to depth images, disparity images, and (registered) point clouds.

openni_launch

Package Summary

Launch files to open an OpenNI device and load all nodelets to convert raw depth/RGB/IR streams to depth images, disparity images, and (registered) point clouds.

Package Summary

Launch files to open an OpenNI device and load all nodelets to convert raw depth/RGB/IR streams to depth images, disparity images, and (registered) point clouds.

Package Summary

Launch files to open an OpenNI device and load all nodelets to convert raw depth/RGB/IR streams to depth images, disparity images, and (registered) point clouds.

Package Summary

Launch files to open an OpenNI device and load all nodelets to convert raw depth/RGB/IR streams to depth images, disparity images, and (registered) point clouds.

Package Summary

Launch files to open an OpenNI device and load all nodelets to convert raw depth/RGB/IR streams to depth images, disparity images, and (registered) point clouds.

Package Summary

Launch files to open an OpenNI device and load all nodelets to convert raw depth/RGB/IR streams to depth images, disparity images, and (registered) point clouds.

Package Summary

Launch files to open an OpenNI device and load all nodelets to convert raw depth/RGB/IR streams to depth images, disparity images, and (registered) point clouds.

Package Summary

Launch files to open an OpenNI device and load all nodelets to convert raw depth/RGB/IR streams to depth images, disparity images, and (registered) point clouds.

openni_launch was introduced in Electric. Select a newer distro above.

New in Fuerte openni_launch is now a unary stack. In Electric it was a package in openni_kinect.

Overview

This package contains launch files for using OpenNI-compliant devices such as the Microsoft Kinect in ROS. It creates a nodelet graph to transform raw data from the device driver into point clouds, disparity images, and other products suitable for processing and visualization.

Quick start

Launch the OpenNI driver. This will launch the full constellation of nodelets:

roslaunch openni_launch openni.launch

To visualize in rviz:

rosrun rviz rviz

Set the Fixed Frame (top left of rviz window) to /camera_depth_optical_frame.

Add a PointCloud2 display, and set the topic to /camera/depth/points. Turning the background to light gray can help with viewing. This is the unregistered point cloud in the frame of the depth (IR) camera. It is not matched with the RGB camera images.

Alternatively you can view the disparity image:

rosrun image_view disparity_view image:=/camera/depth/disparity

Now let's look at a registered point cloud, aligned with the RGB data. Open the dynamic reconfigure GUI:

rosrun rqt_reconfigure rqt_reconfigure

And select /camera/driver from the drop-down menu. Enable the depth_registration checkbox.

Now go back to rviz, and change your PointCloud2 topic to /camera/depth_registered/points. Set Color Transformer to RGB8. You should see a color, 3D point cloud of your scene.

Again, you can view the registered disparity image:

rosrun image_view disparity_view image:=/camera/depth_registered/disparity

To view the color image from the RGB camera outside of rviz:

rosrun image_view image_view image:=/camera/rgb/image_color

or to view the grayscale image:

rosrun image_view image_view image:=/camera/rgb/image_mono

Error during launch

During the launch above, you might encounter the following error:

[ERROR] [1351028964.484342461]: Tried to advertise a service that is already advertised in this node [/camera/depth_registered/image_rect_raw/compressedDepth/set_parameters]
[ERROR] [1351028964.489915028]: Tried to advertise a service that is already advertised in this node [/camera/depth_registered/image_rect_raw/compressed/set_parameters]
[ERROR] [1351028964.495383139]: Tried to advertise a service that is already advertised in this node [/camera/depth_registered/image_rect_raw/theora/set_parameters]

This error occurs because we are trying to publish depth_registered/image_rect_raw from 2 different sources (see the section on Registration below). image_transport sets up multiple services for an image which clash on this occasion. This error will not affect the functionality of the driver, and for the time being should be ignored (http://answers.ros.org/question/12244/complaint-from-openni_launch-on-already-advertised-services/)

Registration

The depth_registered/* topics can be produced in two ways.

If OpenNI registration is enabled:

  • The unregistered camera/depth/* topics are not published.

  • The raw depth image from OpenNI is published in camera/depth_registered instead.

If OpenNI registration is disabled and you have calibrated the cameras to each other:

  • camera/depth_registered/image_raw is computed from camera/depth/image_raw using the camera instrinsics and transform between them.

  • Both registered and unregistered depth outputs are published.
  • This will cost more CPU cycles, since the registration has to be done in software.

Launch files

openni.launch

Launches in one process the device driver and many processing nodelets for turning the raw RGB and depth images into useful products, such as point clouds. Provides default tf tree linking the RGB and depth cameras.

Arguments

camera (string, default: camera)

  • Descriptive name for your device. All published topics are pushed down into the <camera> namespace, and this also affects tf frame ids and some node names. If you are using multiple cameras, use this argument to disambiguate them.
Device driver
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_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.

depth_registration (bool, default: false)

  • If true, use OpenNI's factory-calibrated depth->RGB registration.
load_driver (bool, default: true)
  • If true, load the OpenNI device driver. Set to false if raw data is provided by another source, e.g. bag file playback.

tf frames
rgb_frame_id (string, default: /<camera>_rgb_optical_frame)
  • The tf frame id of the RGB camera.
depth_frame_id (string, default: /<camera>_depth_optical_frame)
  • The tf frame id of the IR camera.

publish_tf (bool, default: true)

  • If true, publish the default (uncalibrated) tf tree. Set to false if extrinsics are provided by another source, e.g. calibration or bag file playback.

Remapping
rgb (string, default: rgb)
  • Remap the rgb namespace.
ir (string, default: ir)
  • Remap the ir namespace.
depth (string, default: depth)
  • Remap the depth namespace.
depth_registered (string, default: depth_registered)
  • Remap the depth_registered namespace.
projector (string, default: projector)
  • Remap the projector namespace.
Launch configuration
debug (bool, default: false)
  • If true, launches nodelet manager in GDB for debugging.

respawn (bool, default: false)

  • If true, enables bond topics between nodelet loaders and the managers and respawns any nodes (manager or loader) that die. This makes the system robust to any node dying, but the proliferation of bond topics can overwhelm introspection tools like rxgraph.

Published Topics

RGB camera
camera/rgb/camera_info (sensor_msgs/CameraInfo)
  • Camera calibration and metadata.
camera/rgb/image_raw (sensor_msgs/Image)
  • Raw image from device. Format is Bayer GRBG for Kinect, YUV422 for PSDK.
camera/rgb/image_mono (sensor_msgs/Image)
  • Monochrome unrectified image.
camera/rgb/image_color (sensor_msgs/Image)
  • Color unrectified image.
camera/rgb/image_rect (sensor_msgs/Image)
  • Monochrome rectified image.
camera/rgb/image_rect_color (sensor_msgs/Image)
  • Color rectified image.
Depth camera
camera/depth/camera_info (sensor_msgs/CameraInfo)
  • Camera calibration and metadata.
camera/depth/image_raw (sensor_msgs/Image)
  • Raw image from device. Contains uint16 depths in mm.
camera/depth/image (sensor_msgs/Image)
  • Unrectified depth image. Contains float depths in m.
camera/depth/image_rect (sensor_msgs/Image)
  • Rectified depth image. Contains float depths in m.
camera/depth/disparity (stereo_msgs/DisparityImage)
  • Disparity image (inversely related to depth), for interop with stereo processing nodes.
camera/depth/points (sensor_msgs/PointCloud2)
  • XYZ point cloud. If using PCL, subscribe as PointCloud<PointXYZ>.
Registered depth camera (aligned with RGB camera)
See Registration.
camera/depth_registered/camera_info (sensor_msgs/CameraInfo)
  • Camera calibration and metadata. Same as camera/rgb/camera_info but time-synced to depth images.
camera/depth_registered/image_raw (sensor_msgs/Image)
  • Raw image from device. Contains uint16 depths in mm.
camera/depth_registered/image (sensor_msgs/Image)
  • Unrectified depth image. Contains float depths in m.
camera/depth_registered/image_rect (sensor_msgs/Image)
  • Rectified depth image. Contains float depths in m.
camera/depth_registered/disparity (stereo_msgs/DisparityImage)
  • Disparity image (inversely related to depth), for interop with stereo processing nodes.
camera/depth_registered/points (sensor_msgs/PointCloud2)
  • XYZRGB point cloud. If using PCL, subscribe as PointCloud<PointXYZRGB>.
IR camera
camera/ir/camera_info (sensor_msgs/CameraInfo)
  • Camera calibration and metadata.
camera/ir/image_raw (sensor_msgs/Image)
  • Raw uint16 IR image.
camera/ir/image_rect (sensor_msgs/Image)
  • Rectified IR image.
IR projector
camera/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.

Provided tf Transforms

/<camera>_rgb_optical_frame/<camera>_depth_optical_frame
  • Default estimate for the transform between the RGB and IR cameras. If OpenNI registration is disabled, this is used with the calibrated camera intrinsics to perform registration.

Parameteres

image_mode (integer, default: 2)

  • Image output mode for the color/grayscale image (1 SXGA_15Hz 1280x1024@15Hz, 2 VGA_30Hz 640x480@30Hz, 3 VGA_25Hz 640x480@25Hz, 4 QVGA_25Hz 320x240@25Hz, 5 QVGA_30Hz 320x240@30Hz, 6 QVGA_60Hz 320x240@60Hz, 7 QQVGA_25Hz 160x120@25Hz, 8 QQVGA_30Hz 160x120@30Hz, 9 QQVGA_60Hz 160x120@60Hz)
depth_mode (integer, default: 2)
  • depth output mode(1 SXGA_15Hz 1280x1024@15Hz, 2 VGA_30Hz 640x480@30Hz, 3 VGA_25Hz 640x480@25Hz, 4 QVGA_25Hz 320x240@25Hz, 5 QVGA_30Hz 320x240@30Hz, 6 QVGA_60Hz 320x240@60Hz, 7 QQVGA_25Hz 160x120@25Hz, 8 QQVGA_30Hz 160x120@30Hz, 9 QQVGA_60Hz 160x120@60Hz)
depth_registration (bool, default: False)
  • Depth data registration
depth_skip (integer, default: 0)
  • Skip N images for every image published (rgb/depth/depth_registered/ir), ie samsample 1/(N+1)
depth_time_offset (double, default: 0)
  • Depth image time offset in seconds
image_time_offset (double, default: 0)
  • Image time offset in seconds
depth_ir_offset_x (double, default: 0)
  • X offset between IR and depth image
depth_ir_offset_y (double, default: 0)
  • Y offset between IR and depth image
z_offset_mm (int, default: 0)
  • Z offset in mm
z_scaling (double, default: 0)
  • scaling factor for depth values

Overview

This package contains launch files for using OpenNI-compliant devices such as the Microsoft Kinect in ROS. It creates a nodelet graph to transform raw data from the device driver into point clouds, disparity images, and other products suitable for processing and visualization.

Starting with ROS Hydro, all the functionality of openni_launch has been moved to rgbd_launch, in order to allow other drivers such as libfreenect (freenect_launch) to use the same code. openni_launch itself contains 1 launch file:

  • launch/openni.launch - Launch RGB-D processing through rgbd_launch with the OpenNI driver.

Quick start

Launch the OpenNI driver. This will launch the full constellation of nodelets:

roslaunch openni_launch openni.launch

To visualize in rviz:

rosrun rviz rviz

Set the Fixed Frame (top left of rviz window) to /camera_depth_optical_frame.

Add a PointCloud2 display, and set the topic to /camera/depth/points. Turning the background to light gray can help with viewing. This is the unregistered point cloud in the frame of the depth (IR) camera. It is not matched with the RGB camera images.

Alternatively you can view the disparity image:

rosrun image_view disparity_view image:=/camera/depth/disparity

Now let's look at a registered point cloud, aligned with the RGB data. Open the dynamic reconfigure GUI:

rosrun rqt_reconfigure rqt_reconfigure

And select /camera/driver from the drop-down menu. Enable the depth_registration checkbox.

Now go back to rviz, and change your PointCloud2 topic to /camera/depth_registered/points. Set Color Transformer to RGB8. You should see a color, 3D point cloud of your scene.

Again, you can view the registered disparity image:

rosrun image_view disparity_view image:=/camera/depth_registered/disparity

To view the color image from the RGB camera outside of rviz:

rosrun image_view image_view image:=/camera/rgb/image_color

or to view the grayscale image:

rosrun image_view image_view image:=/camera/rgb/image_mono

Launch files

openni.launch

Launches in one process the device driver and many processing nodelets for turning the raw RGB and depth images into useful products, such as point clouds. Provides default tf tree linking the RGB and depth cameras.

Arguments

This section only covers arguments that are specific to openni_launch. There are also some common arguments that can be supplied to openni.launch that are documented with rgbd_launch.

camera (string, default: camera)

  • Descriptive name for your device. All published topics are pushed down into the <camera> namespace, and this also affects tf frame ids and some node names. If you are using multiple cameras, use this argument to disambiguate them.
Device driver
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_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.

depth_registration (bool, default: false)

  • If true, use OpenNI's factory-calibrated depth->RGB registration.
load_driver (bool, default: true)
  • If true, load the OpenNI device driver. Set to false if raw data is provided by another source, e.g. bag file playback.

tf frames
rgb_frame_id (string, default: /<camera>_rgb_optical_frame)
  • The tf frame id of the RGB camera.
depth_frame_id (string, default: /<camera>_depth_optical_frame)
  • The tf frame id of the IR camera.

publish_tf (bool, default: true)

  • If true, publish the default (uncalibrated) tf tree. Set to false if extrinsics are provided by another source, e.g. calibration or bag file playback.

tf_prefix (string, default: "")

  • If set, this tf_prefix is prefixed to all frame ids used/generated by openni.launch

Remapping
rgb (string, default: rgb)
  • Remap the rgb namespace.
ir (string, default: ir)
  • Remap the ir namespace.
depth (string, default: depth)
  • Remap the depth namespace.
depth_registered (string, default: depth_registered)
  • Remap the depth_registered namespace.
projector (string, default: projector)
  • Remap the projector namespace.
Launch configuration
debug (bool, default: false)
  • If true, launches nodelet manager in GDB for debugging.

respawn (bool, default: false)

  • If true, enables bond topics between nodelet loaders and the managers and respawns any nodes (manager or loader) that die. This makes the system robust to any node dying, but the proliferation of bond topics can overwhelm introspection tools like rxgraph.

num_worker_threads (int, default: 4)

  • Sets the number of worker threads in the nodelet manager

This section only covers arguments that are specific to openni_launch. There are also some common arguments that can be supplied to openni.launch that are documented with rgbd_launch.

Published Topics

Please consult the documentation at rgbd_launch.

Wiki: openni_launch (last edited 2013-11-14 21:06:21 by PiyushKhandelwal)