Projector.h
Go to the documentation of this file.
00001 #ifndef PANO_PROJECTOR_H_
00002 #define PANO_PROJECTOR_H_
00003 
00004 #include <opencv2/core/core.hpp>
00005 #include <opencv2/imgproc/imgproc.hpp>
00006 namespace pano {
00007 
00008 
00009     class Projector {
00010       friend class SparseProjector;
00011         cv::Mat K, Kinv;
00012         cv::Size outimage_size,input_image_sz;
00013         cv::Mat spherical_coords;
00014         cv::Mat remap1, remap2;
00015         cv::Mat R;
00016         std::vector<cv::Mat> working_mats;
00017     public:
00018         Projector(){}
00024         Projector(const cv::Size& output_size, float theta_range = 2 * CV_PI, float phi_range = CV_PI);
00025 
00026 
00030         void setSRandK(const cv::Size& inputsz,const cv::Mat& R, const cv::Mat& K);
00031 
00032         void projectMat(const cv::Mat& m, cv::Mat& outimage, int filltype = cv::BORDER_TRANSPARENT,const cv::Scalar& value = cv::Scalar());
00033 
00034         ~Projector(void);
00035 
00036         /*** static members *****/
00037 
00048         static cv::Mat createSphericalCoords(const cv::Size& sphere_size = cv::Size(200,200),
00049                                              float theta_range = 2 * CV_PI, float phi_range = CV_PI);
00050 
00051         static void createSphericalCoords(const cv::Size& sphere_size, float theta_0,float theta_1, float phi_0,float phi_1, cv::Mat& spherical_coords);
00055         static cv::Mat createHomogSphrCoords(const cv::Size& sphere_size = cv::Size(200,200),
00056                                              float theta_range = 2 * CV_PI, float phi_range = CV_PI);
00057 
00058         static void getSphereMask(const cv::Mat& onezies, const cv::Mat& remap1,
00059                                   const cv::Mat&remap2, cv::Mat& mask);
00060 
00061         static void projectImage(const cv::Mat& image, const cv::Mat& remap1,
00062                                  const cv::Mat&remap2, cv::Mat & outputimage,int filltype = cv::BORDER_TRANSPARENT,
00063                                  const cv::Scalar& border_value = cv::Scalar());
00064 
00080         static void getSphereRMap(const cv::Mat& K,
00081                                   const cv::Mat& R, cv::Mat& remap1, cv::Mat&remap2,
00082                                   const cv::Mat& spherical_points,
00083                                   const cv::Size& output_size);
00084 
00085         static void getSphereRMapMask(const cv::Mat& K,
00086                                   const cv::Mat& R, cv::Mat& remap, cv::Mat& mask,
00087                                   const cv::Mat& spherical_points,cv::Mat& tm);
00088 
00093         static void getSphereGMap(const cv::Mat& K,
00094                                   const cv::Mat& G, cv::Mat& remap1, cv::Mat&remap2,
00095                                   const cv::Mat& homog_sphr_coords,
00096                                   const cv::Size& output_size);
00097 
00098     private:
00099         static void getSphereRMap(const cv::Mat& K,
00100                                   const cv::Mat& R, cv::Mat& remap1, cv::Mat&remap2,
00101                                   const cv::Mat& spherical_points,
00102                                   const cv::Size& output_size,
00103                                   std::vector<cv::Mat>&
00104                                   working_mats);
00105 
00106         static void getSphereGMap(const cv::Mat& K,
00107                                   const cv::Mat& G, cv::Mat& remap1, cv::Mat&remap2,
00108                                   const cv::Mat& homog_sphr_coords,
00109                                   const cv::Size& output_size,
00110                                   std::vector<cv::Mat>&
00111                                   working_mats);
00112 
00113 
00114     };
00115 
00116 
00117     class SparseProjector{
00118     public:
00119       SparseProjector(){}
00120       SparseProjector(const cv::Size& output_size, const cv::Size& n_grids);
00124       void setSRandK(const cv::Size& inputsz,const cv::Mat& R, const cv::Mat& K, std::vector<int>& roi_ids);
00125       void projectMat(int roi_id, const cv::Mat& m, cv::Mat& outimage, int filltype = cv::BORDER_TRANSPARENT,const cv::Scalar& value = cv::Scalar());
00126       void setWorkingRoi(int id);
00127       cv::Rect getRoi(int id) const{
00128         return rois_[id];
00129       }
00130     private:
00131 
00132       cv::Size output_size_;
00133       cv::Mat spherical_coords_small_;
00134       cv::Size grids_;
00135       std::vector<cv::Rect> rois_;
00136       std::vector<cv::Rect> small_rois_;
00137       cv::Mat remap_,mask_,spherical_coords_,tm_,remap1_,remap2_;
00138       int workingid_;
00139       cv::Mat R_,K_;
00140 
00141     };
00142 }
00143 #endif


pano_core
Author(s): Ethan Rublee
autogenerated on Mon Oct 6 2014 08:04:38