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


cob_people_detection
Author(s): Richard Bormann , Thomas Zwölfer
autogenerated on Mon May 6 2019 02:32:06