face_normalizer.h
Go to the documentation of this file.
00001 #include <opencv2/opencv.hpp>
00002 
00003 #include <iostream>
00004 #include <boost/lexical_cast.hpp>
00005 
00006 using namespace cv;
00007 
00008 namespace FACE
00009 {
00010 enum FEATURE_TYPE
00011 {
00012         LEFTEYE, RIGHTEYE, NOSE, MOUTH,
00013 };
00014 
00016 template<class T>
00017 class FaceFeatures
00018 {
00019 public:
00020 
00022         FaceFeatures<T>()
00023         {
00024         }
00025         ;
00026 
00028         ~FaceFeatures<T>()
00029         {
00030         }
00031         ;
00032 
00033         T lefteye; 
00034         T righteye; 
00035         T nose; 
00036         T mouth; 
00037 
00041         void sub_offset(int& ox, int& oy)
00042         {
00043                 this->lefteye.x -= ox;
00044                 this->lefteye.y -= oy;
00045                 this->righteye.x -= ox;
00046                 this->righteye.y -= oy;
00047                 this->mouth.x -= ox;
00048                 this->mouth.y -= oy;
00049                 this->nose.x -= ox;
00050                 this->nose.y -= oy;
00051         }
00052 
00056         void add_offset(int& ox, int& oy)
00057         {
00058                 this->lefteye.x += ox;
00059                 this->lefteye.y += oy;
00060                 this->righteye.x += ox;
00061                 this->righteye.y += oy;
00062                 this->mouth.x += ox;
00063                 this->mouth.y += oy;
00064                 this->nose.x += ox;
00065                 this->nose.y += oy;
00066         }
00067 
00070         void scale(double scale)
00071         {
00072                 lefteye *= scale;
00073                 righteye *= scale;
00074                 nose *= scale;
00075                 mouth *= scale;
00076         }
00077 
00079         // @return Vector containing lefteye,righteye,nose,mouth
00080         std::vector<T> as_vector()
00081         {
00082                 std::vector<T> vec;
00083                 vec.push_back(lefteye);
00084                 vec.push_back(righteye);
00085                 vec.push_back(nose);
00086                 vec.push_back(mouth);
00087                 return vec;
00088         }
00089         ;
00090 
00092         bool valid()
00093         {
00094                 if (std::isnan(lefteye.x) || std::isnan(lefteye.y))
00095                         return false;
00096                 if (std::isnan(righteye.x) || std::isnan(righteye.y))
00097                         return false;
00098                 if (std::isnan(nose.x) || std::isnan(nose.y))
00099                         return false;
00100                 //if(std::isnan(mouth.x)|| std::isnan(mouth.y)) return false;
00101                 else
00102                         return true;
00103         }
00104 };
00105 
00106 }
00107 ;
00108 
00109 class FaceNormalizer
00110 {
00111 
00112 public:
00118         struct FNConfig
00119         {
00120                 bool eq_ill; 
00121                 bool align; 
00122                 bool resize; 
00123                 bool cvt2gray; 
00124                 bool extreme_illumination_condtions; 
00125         };
00126 
00128         FaceNormalizer()
00129         {
00130         }
00131         ;
00132 
00134         ~FaceNormalizer();
00135 
00138         void init();
00139 
00143         void init(FNConfig& i_config);
00144 
00149         void init(std::string i_classifier_directory, FNConfig& i_config);
00150 
00159         void init(std::string i_classifier_directory, std::string i_storage_directory, FNConfig& i_config, int i_epoch_ctr, bool i_debug, bool i_record_scene);
00160 
00166         bool normalizeFace(cv::Mat & RGB, cv::Size& norm_size);
00167 
00175         bool normalizeFace(cv::Mat& RGB, cv::Mat& XYZ, cv::Size& norm_size, cv::Mat& DM);
00176 
00183         bool normalizeFace(cv::Mat & RGB, cv::Mat& XYZ, cv::Size& norm_size);
00184 
00185         //TODO documentation
00187         bool synthFace(cv::Mat &RGB, cv::Mat& XYZ, cv::Size& norm_size, std::vector<cv::Mat>& synth_images);
00188         bool synth_head_poses(cv::Mat& img, cv::Mat& depth, std::vector<cv::Mat>& synth_images);
00189         bool synth_head_poses_relative(cv::Mat& img, cv::Mat& depth, std::vector<cv::Mat>& synth_images);
00190         bool eliminate_background(cv::Mat& RGB, cv::Mat& XYZ, float background_thresh);
00191         bool isolateFace(cv::Mat& RGB, cv::Mat& XYZ);
00192         bool interpolate_head(cv::Mat& RGB, cv::Mat& XYZ);
00193         bool recordFace(cv::Mat&RGB, cv::Mat& XYZ);
00194 
00200         bool save_scene(cv::Mat& RGB, cv::Mat& XYZ, std::string path);
00201 
00207         bool read_scene(cv::Mat& RGB, cv::Mat& XYZ, std::string path);
00208 
00209         FNConfig config_; 
00210 protected:
00211 
00217         bool normalize_geometry_depth(cv::Mat& img, cv::Mat& depth);
00218 
00224         bool rotate_head(cv::Mat& img, cv::Mat& depth);
00225 
00230         bool features_from_color(cv::Mat& img);
00231 
00236         bool features_from_depth(cv::Mat& depth);
00237 
00244         bool detect_feature(cv::Mat& img, cv::Point2f& coords, FACE::FEATURE_TYPE type);
00245 
00253         bool projectPointCloud(cv::Mat& RGB, cv::Mat& XYZ, cv::Mat& img_res, cv::Mat& depth_res);
00254 
00261         bool projectPoint(cv::Point3f& xyz, cv::Point2f& uv);
00262 
00267         void create_DM(cv::Mat& XYZ, cv::Mat& DM);
00268 
00273         bool normalize_radiometry(cv::Mat& img);
00274 
00280         void extractVChannel(cv::Mat& img, cv::Mat& V);
00281 
00286         void subVChannel(cv::Mat& img, cv::Mat& V);
00287 
00293         void GammaDCT(cv::Mat& img);
00294 
00302         void GammaDoG(cv::Mat& img);
00303 
00308         bool normalize_img_type(cv::Mat& in, cv::Mat& out);
00309 
00313         void dump_features(cv::Mat& img);
00314 
00318         void dump_img(cv::Mat& data, std::string name);
00319 
00320         bool initialized_; 
00321         int epoch_ctr_; 
00322         bool debug_; 
00323         bool record_scene_; 
00324 
00325         std::string storage_directory_; 
00326         std::string classifier_directory_; 
00327 
00328         //intrinsics
00329         cv::Mat cam_mat_; 
00330         cv::Mat dist_coeffs_; 
00331 
00332         CvHaarClassifierCascade* nose_cascade_; 
00333         CvMemStorage* nose_storage_; 
00334 
00335         CvHaarClassifierCascade* eye_l_cascade_; 
00336         CvMemStorage* eye_l_storage_; 
00337 
00338         CvHaarClassifierCascade* eye_r_cascade_; 
00339         CvMemStorage* eye_r_storage_; 
00340 
00341         FACE::FaceFeatures<cv::Point2f> f_det_img_; 
00342         FACE::FaceFeatures<cv::Point3f> f_det_xyz_; 
00343 
00344         cv::Size norm_size_; 
00345         cv::Size input_size_; 
00346 
00347 
00353         template<class T>
00354         void despeckle(cv::Mat& src, cv::Mat& dst)
00355         {
00356                 if (src.channels() == 1)
00357                 {
00358                         T* lptr = src.ptr<T>(1, 0);
00359                         T* rptr = src.ptr<T>(1, 2);
00360                         T* mptr = src.ptr<T>(1, 1);
00361                         T* uptr = src.ptr<T>(0, 1);
00362                         T* dptr = src.ptr<T>(2, 1);
00363 
00364                         int normalizer = 4;
00365 
00366                         for (int px = 2 * src.cols + 2; px < (dst.rows * src.cols); ++px)
00367                         {
00368                                 if (*mptr == 0)
00369                                 {
00370                                         normalizer = 4;
00371                                         if (*lptr == 0)
00372                                                 normalizer -= 1;
00373                                         if (*rptr == 0)
00374                                                 normalizer -= 1;
00375                                         if (*uptr == 0)
00376                                                 normalizer -= 1;
00377                                         if (*dptr == 0)
00378                                                 normalizer -= 1;
00379                                         if (normalizer > 1)
00380                                                 *mptr = (*lptr + *rptr + *uptr + *dptr) / normalizer;
00381                                         else
00382                                                 *mptr = 75;
00383                                 }
00384                                 ++lptr;
00385                                 ++rptr;
00386                                 ++mptr;
00387                                 ++uptr;
00388                                 ++dptr;
00389                         }
00390                 }
00391 
00392                 if (src.channels() == 3)
00393                 {
00394                         cv::Vec<T, 3>* lptr = src.ptr<cv::Vec<T, 3> >(1, 0);
00395                         cv::Vec<T, 3>* rptr = src.ptr<cv::Vec<T, 3> >(1, 2);
00396                         cv::Vec<T, 3>* mptr = src.ptr<cv::Vec<T, 3> >(1, 1);
00397                         cv::Vec<T, 3>* uptr = src.ptr<cv::Vec<T, 3> >(0, 1);
00398                         cv::Vec<T, 3>* dptr = src.ptr<cv::Vec<T, 3> >(2, 1);
00399 
00400                         int normalizer = 4;
00401                         for (int px = 2 * src.cols + 2; px < (dst.rows * src.cols); ++px)
00402                         {
00403                                 if ((*mptr)[0] == 0)
00404                                 {
00405                                         normalizer = 4;
00406                                         if ((*lptr)[0] == 0)
00407                                                 normalizer -= 1;
00408                                         if ((*rptr)[0] == 0)
00409                                                 normalizer -= 1;
00410                                         if ((*uptr)[0] == 0)
00411                                                 normalizer -= 1;
00412                                         if ((*dptr)[0] == 0)
00413                                                 normalizer -= 1;
00414                                         if (normalizer > 1)
00415                                                 cv::divide((*lptr + *rptr + *uptr + *dptr), normalizer, *mptr);
00416                                         else
00417                                                 *mptr = 75;
00418                                 }
00419                                 ++lptr;
00420                                 ++rptr;
00421                                 ++mptr;
00422                                 ++uptr;
00423                                 ++dptr;
00424                         }
00425                 }
00426         }
00427 };


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