rgbd_image_proc is an application available in ccny_rgbd. The application subscribes to the output of RGB-D cameras as produces by the openni_camera (or compatible) driver and performs image rectification, depth-to-rgb registration, depth unwarping, and point cloud generation.

rgbd_image_proc.png

Two drivers are available: rgbd_image_proc_nodelet and rgbd_image_proc_node. Their parameters and topics are identical.

ROS API

Subscribed topics

/camera/rgb/image_color (sensor_msgs/Image)

  • Debayered RGB image
/camera/depth/image_raw (sensor_msgs/Image)
  • Depth image, 16UC1 encoding, in millimeters (0 = invalid data)
/camera/rgb/camera_info (sensor_msgs/CameraInfo)
  • CameraInfo associated with the RGB image
/camera/depth/camera_info (sensor_msgs/CameraInfo)
  • CameraInfo associated with the Depth image

Published topics

/rgbd/rgb (sensor_msgs/Image)

  • Output RGB image (rescaled, rectified)
/rgbd/depth (sensor_msgs/Image)
  • Output Depth image (rescaled, rectified, registered in the RGB frame, and unwarped)
/rgbd/info (sensor_msgs/CameraInfo)
  • Optimal CameraInfo after rescaling and rectification (has 0 distortion). Applies to both images.
/rgbd/cloud (sensor_msgs/PointCloud2)
  • Textured point cloud

Parameters

~queue_size (int, default: 5)

  • input and output queue sizes
~calib_path (string, default: "$HOME/.ros/rgbd_calibration")
  • path to folder where calibration .yml files are stored
~scale (double, default: 1.0)
  • rescaling parameter. Output image dimensions = input image dimensions / scale.
~unwarp (bool, default: true)
  • whether to perform per-pixel unwarping of the depth image based on a polynomial calibration model. If true, calib_path/warp.yml must exist. If false, the depth values won't be modified.
~publish_cloud (bool, default: true)
  • whether to publish the textured sensor_msgs/PointCloud2. Disabling this will increase performance when no point cloud is required.

Wiki: ccny_rgbd/rgbd_image_proc (last edited 2013-02-05 20:33:13 by IvanDryanovski)