Public Attributes
fovis::PrimeSenseCalibrationParameters Struct Reference

Calibration data structure for Kinect / PrimeSense sensors. More...

#include <primesense_depth.hpp>

List of all members.

Public Attributes

CameraIntrinsicsParameters depth_params
double depth_to_rgb_quaternion [4]
double depth_to_rgb_translation [3]
int height
double projector_depth_baseline
CameraIntrinsicsParameters rgb_params
double shift_offset
int width

Detailed Description

Calibration data structure for Kinect / PrimeSense sensors.

This model is taken from the ROS wiki pages. TODO add a link here. Calibration parameters for this model can be fit by following the calibration procedure on the ROS wiki. TODO add a link here.

PrimeSense sensors (e.g., Kinect and PrimeSense) produce a disparity map that can be used to compute a dense depth map. For a given pixel in the IR camera, with pixel coordinates [u, v] and disparity d, the depth to the imaged object can be described as:

\[ z = \frac{8 * \mbox{projector\_depth\_baseline} * f}{(\mbox{shift\_offset} - d)} \]

where $f$ is the IR camera focal length.

The $x$ and $y$ coordinates, in the IR camera frame, can be computed as:

\begin{eqnarray*} x &=& (u - c_x) \frac{z}{f} \\ y &=& (v - c_y) \frac{z}{f} \end{eqnarray*}

where $[c_x, c_y]$ is the center of projection for the IR camera.

Note that this coordinate convention is defined according to standard camera frames in computer graphics and vision, where +Z points along the optical axis away from the camera, +X is to the right, and +y is down. PrimeSense uses a different coordinate frame convention.

Definition at line 49 of file primesense_depth.hpp.


Member Data Documentation

intrinsics of the IR camera.

Definition at line 81 of file primesense_depth.hpp.

Rotation quaternion: [ w, x, y, z ]

Definition at line 76 of file primesense_depth.hpp.

Translation vector: [ x, y, z ]

Definition at line 72 of file primesense_depth.hpp.

image height

Definition at line 58 of file primesense_depth.hpp.

distance from projector to depth camera (m)

Definition at line 67 of file primesense_depth.hpp.

intrinsics of the RGB camera.

Definition at line 85 of file primesense_depth.hpp.

fixed disparity offset.

Definition at line 63 of file primesense_depth.hpp.

image width

Definition at line 54 of file primesense_depth.hpp.


The documentation for this struct was generated from the following file:


libfovis
Author(s): Albert Huang, Maurice Fallon
autogenerated on Thu Jun 6 2019 20:16:12