Computes useful information from a PrimeSenseCalibrationParameters object.
More...
Computes useful information from a PrimeSenseCalibrationParameters object.
Eigen::Matrix4d getDepthUvdToDepthXyz |
( |
| ) |
const |
|
inline |
Compute the 4x4 transformation matrix mapping [ u, v, disparity, 1 ] coordinates to [ x, y, z, w ] homogeneous coordinates in depth camera space.
Eigen::Isometry3d getDepthXyzToRgbXyz |
( |
| ) |
const |
|
inline |
Compute the transformation mapping [ x, y, z, w ] coordinates in depth camera space to RGB camera space.
Eigen::Matrix<double, 3, 4> getRgbXyzToRgbUvw |
( |
| ) |
const |
|
inline |
Compute the 3x4 transformation matrix projecting [ x, y, z, w ] coordinates in RGB camera space to RGB image space.
Eigen::Matrix<double, 3, 4> getDepthUvdToRgbUvw |
( |
| ) |
const |
|
inline |
Convenience function to retrieve the transformation mapping [u, v, disparity] coordinates in the depth camera space to [u, v, w] coordinates in rectified RGB image space. In most cases, the w coordinate will not be 1, so to normalize the [u, v, w] homogeneous coordinate to pixel coordinates, u and v need to be divided by w.
Eigen::Matrix4d getDepthUvdToRgbXyz |
( |
| ) |
const |
|
inline |
Convenience function to retrieve the transformation mapping [u, v, disparity] coordinates in the depth camera space to [X, Y, Z, W] coordinates in RGB XYZ space.
- Returns
- the calibration parameters used to initialize this object.
return the rectification object calculated from the calibration parameters.
The documentation for this class was generated from the following file: