image_pipeline: camera_calibration | depth_image_proc | image_proc | image_rotate | image_view | stereo_image_proc
Package Summary
Contains nodelets for processing depth images such as those produced by OpenNI camera. Functions include creating disparity images and point clouds, as well as registering (reprojecting) a depth image into another camera frame.
- Author: Patrick Mihelich
- License: BSD
- Repository: ros-pkg
- Source: svn https://code.ros.org/svn/ros-pkg/stacks/image_pipeline/trunk/depth_image_proc
New in ROS Fuerte depth_image_proc has found a new home in image_pipeline. In Electric it resided in openni_kinect.
Contents
Overview
depth_image_proc provides basic processing for depth images, much as image_proc does for traditional 2D images. The two packages are complementary; for example, you can (and should!) rectify your depth image before converting it to a point cloud.
A variety of camera technologies can produce depth images:
The Kinect and related devices
- Traditional stereo cameras
- Time-of-flight cameras
See REP 118 for details on depth image representation. The REP recommends that, wherever possible, producers and consumers of depth data use depth images (of type sensor_msgs/Image) instead of sensor_msgs/DisparityImage.
All nodelets (besides convert_metric) in this package support both standard floating point depth images and OpenNI-specific uint16 depth images. Thus when working with OpenNI cameras (e.g. the Kinect), you can save a few CPU cycles by using the uint16 raw topics instead of the float topics.
For an example of depth_image_proc in practice, examine the contents of openni_launch.
Nodelets
depth_image_proc/convert_metric
Nodelet to convert raw uint16 depth image in mm to float depth image in m.Subscribed Topics
image_raw (sensor_msgs/Image)- uint16 depth image in mm, the native OpenNI format.
Published Topics
image (sensor_msgs/Image)- float depth image in m, the recommended format for processing in ROS.
depth_image_proc/disparity
Nodelet to convert depth image to disparity image.Input |
Output |
|
|
Depth image |
Disparity image (colorized by disparity_view) |
Subscribed Topics
left/image_rect (sensor_msgs/Image)- Rectified depth image.
- Camera calibration and metadata. Must contain the baseline, which conventionally is encoded in the right camera P matrix.
Published Topics
left/disparity (stereo_msgs/DisparityImage)- Disparity image (inversely related to depth), for interop with stereo processing nodes. For all other purposes use depth images instead.
Parameters
min_range (double, default: 0.0)- Minimum detectable distance.
- Maximum detectable distance.
- Smallest allowed disparity increment, which relates to the achievable depth range resolution. Defaults to 1/8 pixel.
- Size of message queue for synchronizing subscribed topics.
depth_image_proc/point_cloud_xyz
Nodelet to convert depth image to XYZ point cloud.Input |
Output |
|
|
Depth image |
Point cloud, colorized by distance along Z-axis |
Subscribed Topics
camera_info (sensor_msgs/CameraInfo)- Camera calibration and metadata.
- Rectified depth image.
Published Topics
points (sensor_msgs/PointCloud2)- XYZ point cloud. If using PCL, subscribe as PointCloud<PointXYZ>.
Parameters
queue_size (int, default: 5)- Size of message queue for synchronizing subscribed topics.
depth_image_proc/point_cloud_xyzrgb
Nodelet to combine registered depth image and RGB image into XYZRGB point cloud.Input |
Output |
|
|
Registered depth image |
|
|
|
RGB image |
Color point cloud |
Subscribed Topics
rgb/camera_info (sensor_msgs/CameraInfo)- Camera calibration and metadata.
- Rectified color image.
- Rectified depth image, registered to the RGB camera.
Published Topics
depth_registered/points (sensor_msgs/PointCloud2)- XYZRGB point cloud. If using PCL, subscribe as PointCloud<PointXYZRGB>.
Parameters
queue_size (int, default: 5)- Size of message queue for synchronizing subscribed topics.
depth_image_proc/register
Nodelet to "register" a depth image to another camera frame. Reprojecting the depths requires the calibration parameters of both cameras and, from tf, the extrinsic transform between them.Input |
Output |
|
|
Depth image as captured by depth sensor |
Depth image registered to frame of separate RGB camera |
Subscribed Topics
rgb/camera_info (sensor_msgs/CameraInfo)- RGB camera calibration and metadata.
- Depth camera calibration and metadata.
- Rectified depth image.
Published Topics
depth_registered/camera_info (sensor_msgs/CameraInfo)- Camera calibration and metadata. Same as rgb/camera_info but time-synced to depth_registered/image_rect.
- Reprojected depth image in the RGB camera frame.
Parameters
queue_size (int, default: 5)- Size of message queue for synchronizing subscribed topics.
Required tf Transforms
/depth_optical_frame → /rgb_optical_frame- The transform between the depth and RGB camera optical frames as specified in the headers of the subscribed topics (rendered here as /depth_optical_frame and /rgb_optical_frame).






