Kinect Calibration¶
These are some functions to help work with kinect camera calibration and projective geometry. Tasks:
- Convert the kinect depth image to a metric 3D point cloud
- Convert the 3D point cloud to texture coordinates in the RGB image
Notes about the coordinate systems. There are three coordinate systems to worry about.
Kinect depth image: (u, v, depth) u and v are image coordinates,
(0,0) is the top left corner of the image (640,480) is the bottom right corner of the image.
Depth is the raw 11-bit image from the kinect, where 0 is infinitely far away and larger numbers are closer to the camera (2047 indicates an error pixel)
Kinect rgb image: (u, v) u and v are image coordinates
(0,0) is the top left corner (640,480) is the bottom right corner
XYZ world coordinates: (x, y, z) The 3D world coordinates, in meters, relative to the depth camera.
(0,0,0) is the camera center. Negative Z values are in front of the camera, and the positive Z direction points towards the camera. The X axis points to the right, and the Y axis points up. This is the standard right-handed coordinate system used by OpenGL.
-
calibkinect.
depth2xyzuv
(depth, u=None, v=None)[source]¶ Return a point cloud, an Nx3 array, made by projecting the kinect depth map through intrinsic / extrinsic calibration matrices
You can provide only a portion of the depth image, or a downsampled version of the depth image if you want; just make sure to provide the correct coordinates in the u,v arguments.
Example: # This downsamples the depth image by 2 and then projects to metric point cloud u,v = mgrid[:480:2,:640:2] xyz,uv = depth2xyzuv(freenect.sync_get_depth()[::2,::2], u, v)
# This projects only a small region of interest in the upper corner of the depth image u,v = mgrid[10:120,50:80] xyz,uv = depth2xyzuv(freenect.sync_get_depth()[v,u], u, v)
Parameters: - depth – comes directly from the kinect
- u – image coordinates, same size as depth (default is the original image)
- v – image coordinates, same size as depth (default is the original image)
Returns: xyz - 3D world coordinates in meters (Nx3) uv - image coordinates for the RGB image (Nx3)