face_recognizer_algorithms.h
Go to the documentation of this file.
00001 #include<opencv/cv.h>
00002 #include<iostream>
00003 #include<opencv/highgui.h>
00004 #include<opencv/ml.h>
00005 #include<fstream>
00006 #include<ostream>
00007 #include<limits>
00008 
00009 #include<cob_people_detection/subspace_analysis.h>
00010 
00011 #include<boost/filesystem.hpp>
00012 #include<boost/lexical_cast.hpp>
00013 
00014 namespace ipa_PeopleDetector
00015 {
00016 
00017 enum Classifier
00018 {
00019         CLASS_DIFS, CLASS_SVM, CLASS_KNN, CLASS_RF
00020 };
00021 
00022 enum Method
00023 {
00024         NONE, METH_FISHER, METH_EIGEN, METH_LDA2D, METH_PCA2D
00025 };
00026 
00027 class FaceRecognizerBaseClass
00028 {
00029 public:
00031         FaceRecognizerBaseClass() :
00032                 use_unknown_thresh_(false), trained_(false)
00033         {
00034         }
00035         ;
00036 
00038         virtual ~FaceRecognizerBaseClass()
00039         {
00040         }
00041         ;
00042 
00049         virtual bool trainModel(std::vector<cv::Mat>& img_vec, std::vector<int>& label_vec, int& target_dim)=0;
00050 
00056         virtual void classifyImage(cv::Mat& probe_mat, int& max_prob_index)=0;
00057 
00065         virtual void classifyImage(cv::Mat& probe_mat, int& max_prob_index, cv::Mat& classification_probabilities)=0;
00066 
00068         virtual bool saveModel(boost::filesystem::path& model_file)=0;
00069 
00071         virtual bool loadModel(boost::filesystem::path& model_file)=0;
00072 
00074         inline virtual void activate_unknown_treshold()
00075         {
00076                 use_unknown_thresh_ = true;
00077         }
00078         ;
00079 
00080         bool trained_; 
00081 protected:
00082 
00089         virtual void extractFeatures(std::vector<cv::Mat>& src_vec, cv::Mat& proj_mat, std::vector<cv::Mat>& coeff_vec)=0;
00097         virtual void extractFeatures(cv::Mat& src_mat, cv::Mat& proj_mat, cv::Mat& coeff_mat)=0;
00098 
00105         virtual void calcDIFS(cv::Mat& probe_mat, int& minDIFSindex, double& minDIFS, cv::Mat& probabilities)=0;
00106 
00111         virtual void calc_threshold(cv::Mat& data, double& thresh)=0;
00112 
00117         virtual void calc_threshold(std::vector<cv::Mat>& data, double& thresh)=0;
00121         virtual bool input_param_check(std::vector<cv::Mat>& imgs, std::vector<int>& labels, int& target_dim);
00122 
00128         inline bool is_known(double& distance, double& threshold)
00129         {
00130                 if (distance >= threshold)
00131                         return false;
00132                 return true;
00133         }
00134         ;
00135 
00136         double unknown_thresh_; 
00137         cv::Size source_dim_; 
00138         int target_dim_; 
00139         int num_classes_; 
00140         cv::Mat projection_mat_;
00141         cv::Mat eigenvalues_; 
00142         std::vector<int> model_label_vec_; 
00143         bool use_unknown_thresh_; 
00144 };
00145 
00146 class FaceRecognizer1D: public FaceRecognizerBaseClass
00147 {
00148 
00149 public:
00150         FaceRecognizer1D()
00151         {
00152         }
00153         ;
00154         virtual ~FaceRecognizer1D()
00155         {
00156         }
00157         ;
00158 
00159         virtual void extractFeatures(std::vector<cv::Mat>& src_vec, cv::Mat& proj_mat, std::vector<cv::Mat>& coeff_vec)
00160         {
00161         }
00162         ;
00163         virtual void extractFeatures(cv::Mat& src_vec, cv::Mat& proj_mat, cv::Mat& coeff_vec);
00164         virtual void classifyImage(cv::Mat& probe_mat, int& max_prob_index);
00165         virtual void classifyImage(cv::Mat& probe_mat, int& max_prob_index, cv::Mat& classification_probabilities);
00166         virtual void calcDIFS(cv::Mat& probe_mat, int& minDIFSindex, double& minDIFS, cv::Mat& probabilities);
00167         virtual void calc_threshold(cv::Mat& data, double& thresh);
00168         virtual void calc_threshold(std::vector<cv::Mat>& data, double& thresh)
00169         {
00170         }
00171         ;
00172 
00173         virtual bool saveModel(boost::filesystem::path& model_file);
00174         virtual bool loadModel(boost::filesystem::path& model_file);
00175 
00176         virtual void model_data_mat(std::vector<cv::Mat>& input_data, cv::Mat& data_mat);
00177 
00178 protected:
00179         cv::Mat average_arr_;
00180         cv::Mat model_features_;
00181 
00182 };
00183 
00184 class FaceRecognizer2D: public FaceRecognizerBaseClass
00185 {
00186 
00187 public:
00188         virtual void extractFeatures(std::vector<cv::Mat>& src_vec, cv::Mat& proj_mat, std::vector<cv::Mat>& coeff_vec);
00189         virtual void extractFeatures(cv::Mat& src_vec, cv::Mat& proj_mat, cv::Mat& coeff_vec);
00190         virtual void classifyImage(cv::Mat& probe_mat, int& max_prob_index, cv::Mat& classification_probabilities);
00191         virtual void classifyImage(cv::Mat& probe_mat, int& max_prob_index);
00192         virtual void calcDIFS(cv::Mat& probe_mat, int& minDIFSindex, double& minDIFS, cv::Mat& probabilities);
00193         virtual void calc_threshold(cv::Mat& data, double& thresh)
00194         {
00195         }
00196         ;
00197         virtual void calc_threshold(std::vector<cv::Mat>& data, double& thresh);
00198 
00199         virtual bool saveModel(boost::filesystem::path& model_file);
00200         virtual bool loadModel(boost::filesystem::path& model_file);
00201 
00202 protected:
00203         cv::Mat average_mat_;
00204         std::vector<cv::Mat> model_features_;
00205 };
00206 
00207 class FaceRecognizer_Eigenfaces: public FaceRecognizer1D
00208 {
00209 public:
00210         FaceRecognizer_Eigenfaces()
00211         {
00212         }
00213         ;
00214         virtual ~FaceRecognizer_Eigenfaces()
00215         {
00216         }
00217         ;
00218         virtual bool trainModel(std::vector<cv::Mat>& img_vec, std::vector<int>& label_vec, int& target_dim);
00219 };
00220 
00221 class FaceRecognizer_Fisherfaces: public FaceRecognizer1D
00222 {
00223 public:
00224         FaceRecognizer_Fisherfaces()
00225         {
00226         }
00227         ;
00228         virtual ~FaceRecognizer_Fisherfaces()
00229         {
00230         }
00231         ;
00232         virtual bool trainModel(std::vector<cv::Mat>& img_vec, std::vector<int>& label_vec, int& target_dim);
00233 
00234 protected:
00235         SubspaceAnalysis::LDA lda_;
00236 };
00237 
00238 class FaceRecognizer_LDA2D: public FaceRecognizer2D
00239 {
00240 public:
00241         FaceRecognizer_LDA2D()
00242         {
00243         }
00244         ;
00245         virtual ~FaceRecognizer_LDA2D()
00246         {
00247         }
00248         ;
00249         virtual bool trainModel(std::vector<cv::Mat>& img_vec, std::vector<int>& label_vec, int& target_dim);
00250 };
00251 
00252 class FaceRecognizer_PCA2D: public FaceRecognizer2D
00253 {
00254 public:
00255         FaceRecognizer_PCA2D()
00256         {
00257         }
00258         ;
00259         virtual ~FaceRecognizer_PCA2D()
00260         {
00261         }
00262         ;
00263         virtual bool trainModel(std::vector<cv::Mat>& img_vec, std::vector<int>& label_vec, int& target_dim);
00264 };
00265 
00266 }
00267 ;


cob_people_detection
Author(s): Richard Bormann , Thomas Zwölfer
autogenerated on Fri Aug 28 2015 10:24:12