Public Member Functions | Private Attributes
fovis::PrimeSenseCalibration Class Reference

Computes useful information from a PrimeSenseCalibrationParameters object. More...

#include <primesense_depth.hpp>

List of all members.

Public Member Functions

Eigen::Matrix4d getDepthUvdToDepthXyz () const
Eigen::Matrix< double, 3, 4 > getDepthUvdToRgbUvw () const
Eigen::Matrix4d getDepthUvdToRgbXyz () const
Eigen::Isometry3d getDepthXyzToRgbXyz () const
const
PrimeSenseCalibrationParameters
getParameters () const
const RectificationgetRgbRectification () const
Eigen::Matrix< double, 3, 4 > getRgbXyzToRgbUvw () const
 PrimeSenseCalibration (const PrimeSenseCalibrationParameters &params)
 ~PrimeSenseCalibration ()

Private Attributes

PrimeSenseCalibrationParameters params
Rectificationrgb_rectification

Detailed Description

Computes useful information from a PrimeSenseCalibrationParameters object.

Definition at line 93 of file primesense_depth.hpp.


Constructor & Destructor Documentation

Constructs a PrimeSenseCalibration object using the specified parameters.

Definition at line 11 of file primesense_depth.cpp.

Definition at line 17 of file primesense_depth.cpp.


Member Function Documentation

Eigen::Matrix4d fovis::PrimeSenseCalibration::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.

Definition at line 108 of file primesense_depth.hpp.

Eigen::Matrix<double, 3, 4> fovis::PrimeSenseCalibration::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.

Definition at line 153 of file primesense_depth.hpp.

Eigen::Matrix4d fovis::PrimeSenseCalibration::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.

Definition at line 162 of file primesense_depth.hpp.

Eigen::Isometry3d fovis::PrimeSenseCalibration::getDepthXyzToRgbXyz ( ) const [inline]

Compute the transformation mapping [ x, y, z, w ] coordinates in depth camera space to RGB camera space.

Definition at line 128 of file primesense_depth.hpp.

Returns:
the calibration parameters used to initialize this object.

Definition at line 169 of file primesense_depth.hpp.

return the rectification object calculated from the calibration parameters.

Definition at line 176 of file primesense_depth.hpp.

Eigen::Matrix<double, 3, 4> fovis::PrimeSenseCalibration::getRgbXyzToRgbUvw ( ) const [inline]

Compute the 3x4 transformation matrix projecting [ x, y, z, w ] coordinates in RGB camera space to RGB image space.

Definition at line 140 of file primesense_depth.hpp.


Member Data Documentation

Definition at line 181 of file primesense_depth.hpp.

Definition at line 183 of file primesense_depth.hpp.


The documentation for this class was generated from the following files:


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