gabor_filter_bank.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, Georgia Institute of Technology
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the Georgia Institute of Technology nor the names of
00018  *     its contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 #include <cpl_visual_features/features/gabor_filter_bank.h>
00036 #include <sstream>
00037 
00038 using cv::Mat;
00039 using std::vector;
00040 
00041 namespace cpl_visual_features
00042 {
00043 
00044 //
00045 // Constructors and Initialization
00046 //
00047 GaborFilterBank::GaborFilterBank(int M, int N, double U_l, double U_h, int gabor_size) :
00048     M_(M), N_(N), U_l_(U_l), U_h_(U_h), gabor_size_(gabor_size), calc_var_(true)
00049 {
00050   generateGaborFilters();
00051   // Setup alpha vectors
00052   for(int m = 0; m < M_; ++m)
00053   {
00054     vector<vector<double> > alpha_mu_m;
00055     vector<vector<double> > alpha_sigma_m;
00056 
00057     vector<double> mu_m(N_,0.0);
00058     vector<double> sigma_m(N_,0.0);
00059     alpha_mu_.push_back(mu_m);
00060     alpha_sigma_.push_back(sigma_m);
00061     for(int n = 0; n < N_; ++n)
00062     {
00063       vector<double> mu_mn;
00064       vector<double> sigma_mn;
00065       alpha_mu_m.push_back(mu_mn);
00066       alpha_sigma_m.push_back(sigma_mn);
00067     }
00068 
00069     alpha_base_mu_.push_back(alpha_mu_m);
00070     alpha_base_sigma_.push_back(alpha_sigma_m);
00071   }
00072 }
00073 
00074 void GaborFilterBank::generateGaborFilters()
00075 {
00076   double ln2 = log(2.0);
00077   
00078   // Populate the base x and y matrices for scale m
00079   Mat base_x(gabor_size_, gabor_size_, CV_64FC1);
00080   Mat base_y(gabor_size_, gabor_size_, CV_64FC1);
00081   for (int i = 0; i < base_x.cols; ++i)
00082   {
00083     for (int j = 0; j < base_x.rows; ++j)
00084     {
00085       base_x.at<double>(i,j) = (i - gabor_size_/2);
00086       base_y.at<double>(i,j) = (j - gabor_size_/2);
00087     }
00088   }
00089 
00090   // Iterate through the M_ scale factors
00091   for (int m = 0; m < M_; ++m)
00092   {
00093     vector<Mat> filters_m_c;
00094     vector<Mat> filters_m_w;
00095 
00096     // Calculate filter parameters: a and sigma_x, and sigma_y
00097     double a_m = pow((U_h_ / U_l_), 1.0/(m - 1.0));
00098     double a_m_s = pow(a_m, static_cast<double>(M_ - m));
00099     double u_m = U_h_/a_m_s;
00100     double sigma_u = ((a_m - 1.0)*u_m)/((a_m + 1.0)*sqrt(2*ln2));
00101     double sigma_x = 1.0/(2.0*M_PI*sigma_u);
00102     double z = -2.0*ln2*sigma_u*sigma_u/u_m;
00103 
00104     // Iterate through the N_ orientations
00105     for (int n = 0; n < N_; ++n)
00106     {
00107       // Calculate filter parameters theta and sigma_y
00108       double theta = M_PI / N_*n;
00109       double sigma_v = tan(M_PI/(2.0*n))*(u_m + z)/sqrt(2.0*ln2 - z*z/
00110                                                         (sigma_u*sigma_u));
00111       double sigma_y = 1.0/(2.0*M_PI*sigma_v);
00112 
00113       Mat x_theta = base_x *  cos(theta) + base_y * sin(theta);
00114       Mat y_theta = base_x * -sin(theta) + base_y * cos(theta);
00115 
00116       Mat gabor_mn_r(gabor_size_, gabor_size_, CV_64FC1, 1.0);
00117       Mat gabor_mn_i(gabor_size_, gabor_size_, CV_64FC1, 1.0);
00118       gabor_mn_r *= 1.0/(2.0*M_PI*sigma_x*sigma_y)*a_m_s;
00119       gabor_mn_i *= 1.0/(2.0*M_PI*sigma_x*sigma_y)*a_m_s;
00120 
00121       Mat to_exp(gabor_size_, gabor_size_, CV_64FC1);
00122       to_exp = (x_theta.mul(x_theta)*(1.0/sigma_x*sigma_x) +
00123                 y_theta.mul(y_theta)*(1.0/sigma_y*sigma_y))*-0.5;
00124 
00125       for(int i = 0; i < gabor_size_; i++)
00126       {
00127         for(int j = 0; j < gabor_size_; j++)
00128         {
00129           gabor_mn_r.at<double>(i,j) *= exp(to_exp.at<double>(i,j))*
00130               cos(x_theta.at<double>(i,j)*M_PI*2.0*u_m);
00131           gabor_mn_i.at<double>(i,j) *= exp(to_exp.at<double>(i,j))*
00132               sin(x_theta.at<double>(i,j)*M_PI*2.0*u_m);
00133         }
00134       }
00135       gabor_mn_r*(1.0/a_m);
00136       gabor_mn_i*(1.0/a_m);
00137 
00138       // joint the two filters into a complex matrix
00139       Mat gabor_mn_c(gabor_size_, gabor_size_, CV_64FC2);
00140       vector<Mat> gabor_mns;
00141       gabor_mns.push_back(gabor_mn_r);
00142       gabor_mns.push_back(gabor_mn_i);
00143       merge(gabor_mns, gabor_mn_c);
00144 
00145       filters_m_c.push_back(gabor_mn_c);
00146     }
00147     gabor_c_.push_back(filters_m_c);
00148   }
00149 }
00150 
00151 Mat GaborFilterBank::filterImg(Mat& img, int m, int n, bool use_real)
00152 {
00153   Mat bw_img(img.rows, img.cols, CV_8UC1);
00154   if (img.channels() == 3)
00155   {
00156     cvtColor(img, bw_img, CV_BGR2GRAY);
00157   }
00158   else
00159   {
00160     bw_img = img;
00161   }
00162 
00163   Mat convolved(bw_img.rows, bw_img.cols, bw_img.type());
00164   vector<Mat> components;
00165   split(gabor_c_[m][n], components);
00166   if (use_real)
00167     cv::filter2D(bw_img, convolved, -1, components[0]);
00168   else
00169     cv::filter2D(bw_img, convolved, -1, components[1]);
00170   return convolved;
00171 }
00172 
00173 //
00174 // Core Functions
00175 //
00176 vector<double> GaborFilterBank::extractFeature(Mat& frame)
00177 {
00178   vector<double> feat;
00179   Mat  bw_frame(frame.rows, frame.cols,  CV_8UC1);
00180   Mat use_frame(frame.rows, frame.cols, CV_64FC1);
00181 
00182   if (frame.channels() == 3)
00183   {
00184     cvtColor(frame, bw_frame, CV_BGR2GRAY);
00185   }
00186   else
00187   {
00188     bw_frame = frame;
00189   }
00190   bw_frame.convertTo(use_frame, use_frame.type());
00191 
00192   for(int m = 0; m < M_; ++m)
00193   {
00194     for(int n = 0; n < N_; ++n)
00195     {
00196       Mat D_r = filterImg(use_frame, m, n, true);
00197       Mat D_i = filterImg(use_frame, m, n, false);
00198       cv::imshow("Real", D_r);
00199       cv::imshow("Imaginary", D_i);
00200       cv::waitKey();
00201 
00202       // Calculate the mean and sd of D
00203       double mu_mn = mean(D_r)[0];
00204       Mat use_calc = D_r - mu_mn;
00205       double sigma_mn = std::sqrt(mean(use_calc.mul(use_calc))[0]);
00206 
00207       // Save to the feature and to the sample distribution
00208       feat.push_back(mu_mn);
00209       feat.push_back(sigma_mn);
00210       alpha_base_mu_[m][n].push_back(mu_mn);
00211       alpha_base_sigma_[m][n].push_back(sigma_mn);
00212     }
00213   }
00214   calc_var_ = true;
00215   return feat;
00216 }
00217 
00218 double GaborFilterBank::featureDist(vector<double> f1, vector<double> f2)
00219 {
00220   // TODO: Add sanity check for feature lengths
00221 
00222   double dist = 0.0;
00223 
00224   if (calc_var_)
00225     calcSampleVar();
00226   
00227   for(int m = 0, i = 0; m < M_; ++m)
00228     for(int n = 0; n < N_; ++n, i += 2)
00229     {
00230       double d_mn = std::abs((f1[i] - f2[i])/alpha_mu_[m][n]) +
00231           std::abs((f1[i+1] - f2[i+1])/alpha_sigma_[m][n]);
00232       dist += d_mn;
00233     }
00234 
00235   return dist;   
00236 }
00237 
00238 //
00239 // Helper functions
00240 //
00241 
00242 void GaborFilterBank::calcSampleVar()
00243 {
00244   int I = alpha_base_mu_[0][0].size();
00245   for(int m = 0; m < M_; ++m)
00246   {
00247     for(int n = 0; n < N_; ++n)
00248     {
00249       double mu_mean = 0.0;
00250       double sigma_mean = 0.0;
00251       // Calculate means
00252       for(int i = 0; i < I; ++i)
00253       {
00254         mu_mean += alpha_base_mu_[m][n][i];
00255         sigma_mean += alpha_base_sigma_[m][n][i];
00256       }
00257 
00258       mu_mean /= static_cast<double>(alpha_base_mu_.size());
00259       sigma_mean /= static_cast<double>(alpha_base_mu_.size());
00260 
00261       double std_mu = 0.0;
00262       double std_sigma = 0.0;
00263       // Calculate standard deviations
00264       for(int i = 0; i < I; ++i)
00265       {
00266         std_mu += ((mu_mean - alpha_base_mu_[m][n][i])*
00267                    (mu_mean - alpha_base_mu_[m][n][i]));
00268         std_sigma += ((sigma_mean - alpha_base_sigma_[m][n][i])*
00269                       (sigma_mean - alpha_base_sigma_[m][n][i]));
00270       }
00271 
00272       std_mu = sqrt(std_mu/I);
00273       std_sigma = sqrt(std_sigma/I);
00274 
00275       alpha_mu_[m][n] = std_mu;
00276       alpha_sigma_[m][n] = std_sigma;
00277     }
00278   }   
00279 }
00280 
00281 }


cpl_visual_features
Author(s): Tucker Hermans
autogenerated on Wed Nov 27 2013 11:52:36