depth_image.hpp
Go to the documentation of this file.
00001 #ifndef __fovis_depth_image_hpp__
00002 #define __fovis_depth_image_hpp__
00003 
00004 #include <inttypes.h>
00005 #include "camera_intrinsics.hpp"
00006 #include "depth_source.hpp"
00007 
00008 namespace fovis
00009 {
00010 
00011 class KeypointData;
00012 
00019 class DepthImage : public DepthSource
00020 {
00021   public:
00022     DepthImage(const CameraIntrinsicsParameters& rgb_camera_params,
00023             int depth_width, int depth_height);
00024     ~DepthImage();
00025 
00031     void setDepthImage(const float* depth_data);
00032 
00033     virtual bool haveXyz(int u, int v) ;
00034     virtual void getXyz(OdometryFrame * frame);
00035     virtual void refineXyz(FeatureMatch * matches,
00036                            int num_matches,
00037                            OdometryFrame * frame);
00038 
00039     virtual double getBaseline() const { return 0; }
00040 
00041   private:
00042     int rgbToDepthIndex(double u, double v) const {
00043       return (int)(v * _y_scale) * _depth_width + (int)(u * _x_scale);
00044     }
00045     bool getXyzInterp(KeypointData* kpdata);
00046 
00047     int _rgb_width;
00048     int _rgb_height;
00049 
00050     int _depth_width;
00051     int _depth_height;
00052     float _x_scale;
00053     float _y_scale;
00054 
00055     Eigen::Matrix<double, 3, Eigen::Dynamic>* _rays;
00056     float* _depth_data;
00057 
00058     double _fx_inv;
00059     double _fy_inv;
00060     double _neg_cx_div_fx;
00061     double _neg_cy_div_fy;
00062 };
00063 
00064 }
00065 #endif


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