Notice: MediaWiki has been updated. Report any rough edges to marcan@marcan.st

Imaging Information

From OpenKinect
Jump to: navigation, search

RGB Camera

The RGB camera has a slightly larger angle of view than the Depth camera. For computer vision applications, it can be calibrated using standard techniques, e.g from OpenCV.

Laser Illuminator

The IR emitter projects an irregular pattern of IR dots of varying intensities. The Depth Camera reconstructs a depth image by recognizing the distortion in this pattern. Apparent when looking at the IR view in the rgbdemo application, are nine much brighter dots in a regular grid: one in the center of the view and 8 aligned in a square formation near the edges. (Perhaps these can be used to aid in easier and more accurate calibration?)

Depth Camera

Lots of information on calibrating the depth camera is available on the ROS kinect_node page.

From their data, a basic first order approximation for converting the raw 11-bit disparity value to a depth value in centimeters is: 100/(-0.00307 * rawDisparity + 3.33). This approximation is approximately 10 cm off at 4 m away, and less than 2 cm off within 2.5 m.

A better approximation is given by Stéphane Magnenat in this post: distance = 0.1236 * tan(rawDisparity / 2842.5 + 1.1863) in meters. Adding a final offset term of -0.037 centers the original ROS data. The tan approximation has a sum squared difference of .33 cm while the 1/x approximation is about 1.7 cm.

Once you have the distance using the measurement above, a good approximation for converting (i, j, z) to (x,y,z) is:

x = (i - w / 2) * (z + minDistance) * scaleFactor
y = (j - h / 2) * (z + minDistance) * scaleFactor
z = z
Where
minDistance = -10
scaleFactor = .0021.
These values were found by hand.

Color/Depth Mapping

To enable accurate mapping between depth pixels (voxels) and color pixels and obtain colored point clouds, the intrinsics parameters of both depth and color cameras are required (focal distances, distortion coefficients and image center), but their relative position and orientation in the world coordinate frame also need to be estimated. A preliminary attempt to extract all these parameters in a semi-automatic way is described there [1]. A matlab toolbox that estimates all these parameters jointly is [2].

Depth camera accuracy

From PrimeSense reference design for PS1080 (see this thread for explanations):

Field of View (Horizontal, Vertical, Diagonal) = 58° H, 45° V, 70° D
Spatial x/y resolution (@ 2m distance from sensor) = 3mm
Depth z resolution (@ 2m distance from sensor) = 1cm
Operation range = 0.8m - 3.5m