primesense_depth.hpp
Go to the documentation of this file.
00001 #ifndef __fovis_primesense_depth_hpp__
00002 #define __fovis_primesense_depth_hpp__
00003 
00004 #include <inttypes.h>
00005 #include <assert.h>
00006 #include "feature_match.hpp"
00007 #include "camera_intrinsics.hpp"
00008 #include "rectification.hpp"
00009 #include "depth_source.hpp"
00010 
00011 namespace fovis
00012 {
00013 
00049 struct PrimeSenseCalibrationParameters
00050 {
00054   int width;
00058   int height;
00059 
00063   double shift_offset;
00067   double projector_depth_baseline;
00068 
00072   double depth_to_rgb_translation[3];
00076   double depth_to_rgb_quaternion[4];
00077 
00081   CameraIntrinsicsParameters depth_params;
00085   CameraIntrinsicsParameters rgb_params;
00086 };
00087 
00093 class PrimeSenseCalibration
00094 {
00095   public:
00100     PrimeSenseCalibration(const PrimeSenseCalibrationParameters& params);
00101     ~PrimeSenseCalibration();
00102 
00108     Eigen::Matrix4d getDepthUvdToDepthXyz() const {
00109       double fx_inv = 1 / params.depth_params.fx;
00110       double pdb_inv = 1 / params.projector_depth_baseline;
00111       double a = -0.125 * fx_inv * pdb_inv;
00112       double b = 0.125 * params.shift_offset * fx_inv * pdb_inv;
00113       double cx = params.depth_params.cx;
00114       double cy = params.depth_params.cy;
00115       Eigen::Matrix4d result;
00116       result <<
00117         fx_inv, 0, 0, -cx * fx_inv,
00118         0, fx_inv, 0, -cy * fx_inv,
00119         0, 0, 0, 1,
00120         0, 0, a, b;
00121       return result;
00122     }
00123 
00128     Eigen::Isometry3d getDepthXyzToRgbXyz() const {
00129       Eigen::Isometry3d result = Eigen::Isometry3d::Identity();
00130       result.translate(Eigen::Vector3d(params.depth_to_rgb_translation));
00131       const double *q = params.depth_to_rgb_quaternion;
00132       result.rotate(Eigen::Quaterniond(q[0], q[1], q[2], q[3]));
00133       return result;
00134     }
00135 
00140     Eigen::Matrix<double, 3, 4> getRgbXyzToRgbUvw() const {
00141       return rgb_rectification->getInputCameraParameters().toProjectionMatrix();
00142     }
00143 
00144     // ============= convenience functions =================
00145 
00153     Eigen::Matrix<double, 3, 4> getDepthUvdToRgbUvw() const {
00154       return getRgbXyzToRgbUvw() * getDepthXyzToRgbXyz().matrix() * getDepthUvdToDepthXyz();
00155     }
00156 
00162     Eigen::Matrix4d getDepthUvdToRgbXyz() const {
00163       return getDepthXyzToRgbXyz().matrix() * getDepthUvdToDepthXyz();
00164     }
00165 
00169     const PrimeSenseCalibrationParameters& getParameters() const {
00170       return params;
00171     }
00172 
00176     const Rectification* getRgbRectification() const {
00177       return rgb_rectification;
00178     }
00179 
00180   private:
00181     PrimeSenseCalibrationParameters params;
00182 
00183     Rectification* rgb_rectification;
00184 };
00185 
00192 class PrimeSenseDepth : public DepthSource
00193 {
00194   public:
00195     PrimeSenseDepth(const PrimeSenseCalibration* calib);
00196     ~PrimeSenseDepth();
00197 
00198     void setDisparityData(const uint16_t* disparity);
00199 
00200     bool getXyz(int u, int v, Eigen::Vector3d & xyz);
00201     void getXyz(OdometryFrame * frame);
00202     void refineXyz(FeatureMatch * matches,
00203                    int num_matches,
00204                    OdometryFrame * frame);
00205 
00218     inline uint16_t getDisparity(int rgb_u, int rgb_v) const;
00219 
00223     inline uint16_t getDisparityAtIRPixel(int ir_u, int ir_v) const;
00224 
00225     inline double getBaseline() const;
00226 
00227     inline bool haveXyz(int u, int v);
00228 
00229   private:
00230     bool haveXyz(float u_f, float v_f);
00231 
00232     bool getXyzFast(KeypointData* kpdata);
00233     bool getXyzInterp(KeypointData* kpdata);
00234 
00235     int _ir_width;
00236     int _ir_height;
00237 
00238     const PrimeSenseCalibration* _calib;
00239 
00240     uint16_t* _disparity;
00241 
00242     // for each RGB camera pixel, stores the index of the corresponding
00243     // disparity image pixel (v*width + u)
00244     uint32_t* _rgb_to_disparity_map;
00245 
00246     uint32_t _disparity_map_max_index;
00247 
00248     Eigen::Matrix4d* _uvd1_d_to_xyz_c;
00249 };
00250 
00251 uint16_t
00252 PrimeSenseDepth::getDisparity(int u, int v) const
00253 {
00254   int rgb_index = v * _ir_width + u;
00255   uint32_t disparity_index = _rgb_to_disparity_map[rgb_index];
00256   if(disparity_index < _disparity_map_max_index) {
00257     return _disparity[disparity_index];
00258   } else {
00259     return 0;
00260   }
00261 }
00262 
00263 uint16_t
00264 PrimeSenseDepth::getDisparityAtIRPixel(int ir_u, int ir_v) const
00265 {
00266   assert(ir_u >= 0 && ir_v >= 0 && ir_u < _ir_width && ir_v < _ir_height);
00267   return _disparity[ir_v * _ir_width + ir_u];
00268 }
00269 
00270 double
00271 PrimeSenseDepth::getBaseline() const
00272 {
00273   return _calib->getParameters().projector_depth_baseline;
00274 }
00275 
00276 bool
00277 PrimeSenseDepth::haveXyz(int u, int v)
00278 {
00279   int rgb_index = v * _ir_width + u;
00280   uint32_t disparity_index = _rgb_to_disparity_map[rgb_index];
00281   return disparity_index < _disparity_map_max_index;
00282 }
00283 
00284 }
00285 #endif


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