rgbd_frame.h
Go to the documentation of this file.
00001 
00024 #ifndef RGBDTOOLS_RGBD_FRAME_H
00025 #define RGBDTOOLS_RGBD_FRAME_H
00026 
00027 #include <vector>
00028 #include <boost/filesystem.hpp>
00029 #include <pcl/io/pcd_io.h>
00030 #include <opencv2/core/core.hpp>
00031 
00032 #include "rgbdtools/types.h"
00033 #include "rgbdtools/header.h"
00034 #include "rgbdtools/rgbd_util.h"
00035 
00036 namespace rgbdtools {
00037 
00047 class RGBDFrame
00048 {
00049   public:
00050 
00051     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00052 
00055     RGBDFrame();
00056 
00057     RGBDFrame(const RGBDFrame& other);
00058 
00065     RGBDFrame(const cv::Mat& rgb_img_in,
00066               const cv::Mat& depth_img_in,
00067               const cv::Mat& intr_in,
00068               const Header& header_in);
00069 
00070     RGBDFrame(const cv::Mat& rgb_img_in,
00071               const cv::Mat& depth_img_in,
00072               const cv::Mat& intr_in,
00073               const cv::Mat& dist_in,
00074               const Header& header_in);
00075 
00076     int index;
00077     
00078     Header header; 
00079     cv::Mat rgb_img;         
00080     cv::Mat depth_img;       
00081     cv::Mat intr;
00082     cv::Mat dist;
00088     //image_geometry::PinholeCameraModel model;
00089     
00090     KeypointVector keypoints;         
00091     cv::Mat        descriptors;       
00092 
00093     BoolVector     kp_valid;          
00094     Vector3fVector kp_means;          
00095     Matrix3fVector kp_covariances;    
00096 
00097     int n_valid_keypoints;            
00098     bool used;
00107     void computeDistributions(
00108       double max_z = 5.5,
00109       double max_stdev_z = 0.03);    
00110 
00114     void constructFeaturePointCloud(PointCloudFeature& cloud);
00115 
00125     void constructDensePointCloud(PointCloudT& cloud,
00126                                   double max_z = 5.5,
00127                                   double max_stdev_z = 0.03) const;
00128     void getPointsDist(std::vector<std::vector<float> > points,std::vector<std::vector<double> > *dists);
00141     static bool save(const RGBDFrame& frame, const std::string& path);
00142 
00154     static bool load(RGBDFrame& frame, const std::string& path);
00155     
00156   protected:
00157 
00163     static const double Z_STDEV_CONSTANT = 0.001425;
00164     
00169     double getVarZ(double z) const;
00170     
00175     double getStdDevZ(double z) const;
00176 
00189     void getGaussianDistribution(int u, int v, double& z_mean, double& z_var) const;
00190     
00206     void getGaussianMixtureDistribution(int u, int v, double& z_mean, double& z_var) const;
00207 };
00208 
00209 } // namespace rgbdtools
00210 
00211 #endif // RGBDTOOLS_RGBD_FRAME_H
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends


lib_rgbdtools
Author(s): Ivan Dryanovski
autogenerated on Tue Aug 27 2013 10:33:54