00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 #ifndef __MATCHER_H__
00023 #define __MATCHER_H__
00024 
00025 #include <stdio.h>
00026 #include <stdlib.h>
00027 #include <string.h>
00028 #include <iostream>
00029 #include <math.h>
00030 #include <emmintrin.h>
00031 #include <algorithm>
00032 #include <vector>
00033 
00034 #include "matrix.h"
00035 
00036 class Matcher {
00037 
00038 public:
00039 
00040   
00041   struct parameters {
00042   
00043     int32_t nms_n;                  
00044     int32_t nms_tau;                
00045     int32_t match_binsize;          
00046     int32_t match_radius;           
00047     int32_t match_disp_tolerance;   
00048     int32_t outlier_disp_tolerance; 
00049     int32_t outlier_flow_tolerance; 
00050     int32_t multi_stage;            
00051     int32_t half_resolution;        
00052     int32_t refinement;             
00053     double  f,cu,cv,base;           
00054     
00055     
00056     parameters () {
00057       nms_n                  = 3;
00058       nms_tau                = 50;
00059       match_binsize          = 50;
00060       match_radius           = 200;
00061       match_disp_tolerance   = 2;
00062       outlier_disp_tolerance = 5;
00063       outlier_flow_tolerance = 5;
00064       multi_stage            = 1;
00065       half_resolution        = 1;
00066       refinement             = 1;
00067     }
00068   };
00069 
00070   
00071   Matcher(parameters param);
00072 
00073   
00074   ~Matcher();
00075   
00076   
00077   void setIntrinsics(double f,double cu,double cv,double base) {
00078     param.f = f;
00079     param.cu = cu;
00080     param.cv = cv;
00081     param.base = base;
00082   }
00083 
00084   
00085   struct p_match {
00086     float   u1p,v1p; 
00087     int32_t i1p;     
00088     float   u2p,v2p; 
00089     int32_t i2p;     
00090     float   u1c,v1c; 
00091     int32_t i1c;     
00092     float   u2c,v2c; 
00093     int32_t i2c;     
00094     p_match(){}
00095     p_match(float u1p,float v1p,int32_t i1p,float u2p,float v2p,int32_t i2p,
00096             float u1c,float v1c,int32_t i1c,float u2c,float v2c,int32_t i2c):
00097             u1p(u1p),v1p(v1p),i1p(i1p),u2p(u2p),v2p(v2p),i2p(i2p),
00098             u1c(u1c),v1c(v1c),i1c(i1c),u2c(u2c),v2c(v2c),i2c(i2c) {}
00099   };
00100 
00101   
00102   
00103   
00104   
00105   
00106   
00107   
00108   
00109   
00110   
00111   void pushBack (uint8_t *I1,uint8_t* I2,int32_t* dims,const bool replace);
00112   
00113   
00114   
00115   
00116   
00117   void pushBack (uint8_t *I1,int32_t* dims,const bool replace) { pushBack(I1,0,dims,replace); }
00118 
00119   
00120   
00121   
00122   
00123   void matchFeatures(int32_t method, Matrix *Tr_delta = 0);
00124 
00125   
00126   
00127   void bucketFeatures(int32_t max_features,float bucket_width,float bucket_height);
00128 
00129   
00130   std::vector<Matcher::p_match> getMatches() { return p_matched_2; }
00131 
00132   
00133   
00134   
00135   float getGain (std::vector<int32_t> inliers);
00136 
00137 private:
00138 
00139   
00140   struct maximum {
00141     int32_t u;   
00142     int32_t v;   
00143     int32_t val; 
00144     int32_t c;   
00145     int32_t d1,d2,d3,d4,d5,d6,d7,d8; 
00146     maximum() {}
00147     maximum(int32_t u,int32_t v,int32_t val,int32_t c):u(u),v(v),val(val),c(c) {}
00148   };
00149   
00150   
00151   struct range {
00152     float u_min[4];
00153     float u_max[4];
00154     float v_min[4];
00155     float v_max[4];
00156   };
00157   
00158   struct delta {
00159     float val[8];
00160     delta () {}
00161     delta (float v) {
00162       for (int32_t i=0; i<8; i++)
00163         val[i] = v;
00164     }
00165   };
00166   
00167   
00168   inline int32_t getAddressOffsetImage (const int32_t& u,const int32_t& v,const int32_t& width) {
00169     return v*width+u;
00170   }
00171 
00172   
00173   void nonMaximumSuppression (int16_t* I_f1,int16_t* I_f2,const int32_t* dims,std::vector<Matcher::maximum> &maxima,int32_t nms_n);
00174 
00175   
00176   inline uint8_t saturate(int16_t in);
00177   void filterImageAll (uint8_t* I,uint8_t* I_du,uint8_t* I_dv,int16_t* I_f1,int16_t* I_f2,const int* dims);
00178   void filterImageSobel (uint8_t* I,uint8_t* I_du,uint8_t* I_dv,const int* dims);
00179   inline void computeDescriptor (const uint8_t* I_du,const uint8_t* I_dv,const int32_t &bpl,const int32_t &u,const int32_t &v,uint8_t *desc_addr);
00180   inline void computeSmallDescriptor (const uint8_t* I_du,const uint8_t* I_dv,const int32_t &bpl,const int32_t &u,const int32_t &v,uint8_t *desc_addr);
00181   void computeDescriptors (uint8_t* I_du,uint8_t* I_dv,const int32_t bpl,std::vector<Matcher::maximum> &maxima);
00182   
00183   void getHalfResolutionDimensions(const int32_t *dims,int32_t *dims_half);
00184   uint8_t* createHalfResolutionImage(uint8_t *I,const int32_t* dims);
00185 
00186   
00187   
00188   
00189   
00190   
00191   
00192   
00193   
00194   
00195   void computeFeatures (uint8_t *I,const int32_t* dims,int32_t* &max1,int32_t &num1,int32_t* &max2,int32_t &num2,uint8_t* &I_du,uint8_t* &I_dv,uint8_t* &I_du_full,uint8_t* &I_dv_full);
00196 
00197   
00198   void computePriorStatistics (std::vector<Matcher::p_match> &p_matched,int32_t method);
00199   void createIndexVector (int32_t* m,int32_t n,std::vector<int32_t> *k,const int32_t &u_bin_num,const int32_t &v_bin_num);
00200   inline void findMatch (int32_t* m1,const int32_t &i1,int32_t* m2,const int32_t &step_size,
00201                          std::vector<int32_t> *k2,const int32_t &u_bin_num,const int32_t &v_bin_num,const int32_t &stat_bin,
00202                          int32_t& min_ind,int32_t stage,bool flow,bool use_prior,double u_=-1,double v_=-1);
00203   void matching (int32_t *m1p,int32_t *m2p,int32_t *m1c,int32_t *m2c,
00204                  int32_t n1p,int32_t n2p,int32_t n1c,int32_t n2c,
00205                  std::vector<Matcher::p_match> &p_matched,int32_t method,bool use_prior,Matrix *Tr_delta = 0);
00206 
00207   
00208   void removeOutliers (std::vector<Matcher::p_match> &p_matched,int32_t method);
00209 
00210   
00211   bool parabolicFitting(const uint8_t* I1_du,const uint8_t* I1_dv,const int32_t* dims1,
00212                         const uint8_t* I2_du,const uint8_t* I2_dv,const int32_t* dims2,
00213                         const float &u1,const float &v1,
00214                         float       &u2,float       &v2,
00215                         Matrix At,Matrix AtA,
00216                         uint8_t* desc_buffer);
00217   void relocateMinimum(const uint8_t* I1_du,const uint8_t* I1_dv,const int32_t* dims1,
00218                        const uint8_t* I2_du,const uint8_t* I2_dv,const int32_t* dims2,
00219                        const float &u1,const float &v1,
00220                        float       &u2,float       &v2,
00221                        uint8_t* desc_buffer);
00222   void refinement (std::vector<Matcher::p_match> &p_matched,int32_t method);
00223 
00224   
00225   inline float mean(const uint8_t* I,const int32_t &bpl,const int32_t &u_min,const int32_t &u_max,const int32_t &v_min,const int32_t &v_max);
00226 
00227   
00228   parameters param;
00229   int32_t    margin;
00230   
00231   int32_t *m1p1,*m2p1,*m1c1,*m2c1;
00232   int32_t *m1p2,*m2p2,*m1c2,*m2c2;
00233   int32_t n1p1,n2p1,n1c1,n2c1;
00234   int32_t n1p2,n2p2,n1c2,n2c2;
00235   uint8_t *I1p,*I2p,*I1c,*I2c;
00236   uint8_t *I1p_du,*I2p_du,*I1c_du,*I2c_du;
00237   uint8_t *I1p_dv,*I2p_dv,*I1c_dv,*I2c_dv;
00238   uint8_t *I1p_du_full,*I2p_du_full,*I1c_du_full,*I2c_du_full; 
00239   uint8_t *I1p_dv_full,*I2p_dv_full,*I1c_dv_full,*I2c_dv_full; 
00240   int32_t dims_p[3],dims_c[3];
00241 
00242   std::vector<Matcher::p_match> p_matched_1;
00243   std::vector<Matcher::p_match> p_matched_2;
00244   std::vector<Matcher::range>   ranges;
00245 };
00246 
00247 #endif
00248