face_recognizer.cpp
Go to the documentation of this file.
00001 
00061 #ifdef __LINUX__
00062         #include "cob_people_detection/face_recognizer.h"
00063         #include "cob_vision_utils/GlobalDefines.h"
00064 #else
00065 #include "cob_vision/cob_people_detection/common/include/cob_people_detection/PeopleDetector.h"
00066 #include "cob_common/cob_vision_utils/common/include/cob_vision_utils/GlobalDefines.h"
00067 #endif
00068 
00069 // stream
00070 #include <fstream>
00071 
00072 // opencv
00073 #include <opencv2/opencv.hpp>
00074 
00075 // boost
00076 #include "boost/filesystem/operations.hpp"
00077 #include "boost/filesystem/convenience.hpp"
00078 
00079 #include <sys/time.h>
00080 
00081 namespace fs = boost::filesystem;
00082 using namespace ipa_PeopleDetector;
00083 
00084 ipa_PeopleDetector::FaceRecognizer::FaceRecognizer(void)
00085 {
00086         m_eigenvectors_ipl = 0;
00087 
00088 }
00089 
00090 ipa_PeopleDetector::FaceRecognizer::~FaceRecognizer(void)
00091 {
00092         if (m_eigenvectors_ipl != 0)
00093         {
00094                 for (uint i=0; i<m_eigenvectors.size(); i++)
00095                         cvReleaseImage(&(m_eigenvectors_ipl[i]));
00096                 cvFree(&m_eigenvectors_ipl);
00097         }
00098 }
00099 
00100 unsigned long ipa_PeopleDetector::FaceRecognizer::init(std::string data_directory, int norm_size, bool norm_illumination, bool norm_align, bool norm_extreme_illumination,
00101                 int metric, bool debug, std::vector<std::string>& identification_labels_to_recognize, int subs_meth, int feature_dim, bool use_unknown_thresh, bool use_depth)
00102 {
00103         // parameters
00104         m_data_directory = boost::filesystem::path(data_directory);
00105         m_data_directory /= "training_data";
00106         assertDirectories(m_data_directory);
00107 
00108         m_norm_size = norm_size;
00109         m_metric = metric;
00110         m_debug = debug;
00111         m_depth_mode = use_depth;
00112         m_use_unknown_thresh = use_unknown_thresh;
00113 
00114         m_feature_dim = feature_dim;
00115 
00116         switch(subs_meth)
00117         {
00118         case 0:
00119         {
00120                 m_subs_meth = ipa_PeopleDetector::METH_FISHER;
00121                 eff_color = new ipa_PeopleDetector::FaceRecognizer_Fisherfaces();
00122                 break;
00123         }
00124         case 1:
00125         {
00126                 m_subs_meth = ipa_PeopleDetector::METH_EIGEN;
00127                 eff_color = new ipa_PeopleDetector::FaceRecognizer_Eigenfaces();
00128                 break;
00129         }
00130         case 2:
00131         {
00132                 m_subs_meth = ipa_PeopleDetector::METH_LDA2D;
00133                 eff_color = new ipa_PeopleDetector::FaceRecognizer_LDA2D();
00134                 break;
00135         }
00136         case 3:
00137         {
00138                 m_subs_meth = ipa_PeopleDetector::METH_PCA2D;
00139                 eff_color = new ipa_PeopleDetector::FaceRecognizer_PCA2D();
00140                 break;
00141         }
00142         default:
00143         {
00144                 m_subs_meth = ipa_PeopleDetector::METH_FISHER;
00145                 eff_color = new ipa_PeopleDetector::FaceRecognizer_Fisherfaces();
00146                 break;
00147         }
00148         };
00149 
00150         FaceNormalizer::FNConfig fn_cfg;
00151         fn_cfg.eq_ill = norm_illumination;
00152         fn_cfg.align = norm_align;
00153         fn_cfg.resize = true;
00154         fn_cfg.cvt2gray = true;
00155         fn_cfg.extreme_illumination_condtions = norm_extreme_illumination;
00156 
00157         std::string classifier_directory = data_directory + "haarcascades/";
00158         //std::string storage_directory="/share/goa-tz/people_detection/eval/KinectIPA/";
00159         std::string storage_directory = "/share/goa-tz/people_detection/eval/KinectIPA/";
00160         face_normalizer_.init(classifier_directory, storage_directory, fn_cfg, 0, false, false);
00161 
00162         // load model
00163         return loadRecognitionModel(identification_labels_to_recognize);
00164 }
00165 
00166 unsigned long ipa_PeopleDetector::FaceRecognizer::initTraining(std::string data_directory, int norm_size, bool norm_illumination, bool norm_align, bool norm_extreme_illumination,
00167                 bool debug, std::vector<cv::Mat>& face_images, std::vector<cv::Mat>& face_depthmaps, bool use_depth)
00168 {
00169         // parameters
00170         m_data_directory = boost::filesystem::path(data_directory);
00171         m_data_directory /= "training_data";
00172         assertDirectories(m_data_directory);
00173         m_norm_size = norm_size;
00174         m_debug = debug;
00175         m_depth_mode = use_depth;
00176 
00177         FaceNormalizer::FNConfig fn_cfg;
00178         fn_cfg.eq_ill = norm_illumination;
00179         fn_cfg.align = norm_align;
00180         fn_cfg.resize = true;
00181         fn_cfg.cvt2gray = true;
00182         fn_cfg.extreme_illumination_condtions = norm_extreme_illumination;
00183 
00184         std::string classifier_directory = data_directory + "haarcascades/";
00185         //std::string storage_directory="/share/goa-tz/people_detection/eval/KinectIPA/";
00186         std::string storage_directory = "/share/goa-tz/people_detection/eval/KinectIPA/";
00187         face_normalizer_.init(classifier_directory, storage_directory, fn_cfg, 0, false, false);
00188         // load model
00189         m_current_label_set.clear(); // keep empty to load all available data
00190         return loadTrainingData(face_images, m_current_label_set);
00191 }
00192 
00193 unsigned long ipa_PeopleDetector::FaceRecognizer::addFace(cv::Mat& color_image, cv::Mat& depth_image, cv::Rect& face_bounding_box, cv::Rect& head_bounding_box, std::string label,
00194                 std::vector<cv::Mat>& face_images, std::vector<cv::Mat>& face_depthmaps)
00195 {
00196         // secure this function with a mutex
00197         boost::lock_guard<boost::mutex> lock(m_data_mutex);
00198 
00199         //cv::Rect combined_face_bounding_box=cv::Rect(face_bounding_box.x+head_bounding_box.x,face_bounding_box.y+head_bounding_box.y,face_bounding_box.width,face_bounding_box.height);
00200         //cv::Mat roi_color = color_image(combined_face_bounding_box);
00201         cv::Mat roi_color = color_image(face_bounding_box);     // color image has size of head area, not only face area
00202         cv::Mat roi_depth_xyz = depth_image(face_bounding_box).clone();
00203         cv::Size norm_size = cv::Size(m_norm_size, m_norm_size);
00204         cv::Mat roi_depth;
00205         //if(!face_normalizer_.normalizeFace(roi_color,roi_depth_xyz,norm_size)) ;
00206         // this is probably obsolete:  face_normalizer_.recordFace(roi_color, roi_depth_xyz);
00207 
00208         if (!face_normalizer_.normalizeFace(roi_color, roi_depth_xyz, norm_size))
00209                 return ipa_Utils::RET_FAILED;
00210 
00211         // Save image
00212         face_images.push_back(roi_color);
00213         face_depthmaps.push_back(roi_depth_xyz);
00214         m_face_labels.push_back(label);
00215         dm_exist.push_back(true);
00216 
00217         return ipa_Utils::RET_OK;
00218 
00219 }
00220 
00221 unsigned long ipa_PeopleDetector::FaceRecognizer::updateFaceLabels(std::string old_label, std::string new_label)
00222 {
00223         for (int i=0; i<(int)m_face_labels.size(); i++)
00224         {
00225                 if (m_face_labels[i].compare(old_label) == 0)
00226                         m_face_labels[i] = new_label;
00227         }
00228         return ipa_Utils::RET_OK;
00229 }
00230 
00231 unsigned long ipa_PeopleDetector::FaceRecognizer::updateFaceLabel(int index, std::string new_label)
00232 {
00233         m_face_labels[index] = new_label;
00234         return ipa_Utils::RET_OK;
00235 }
00236 
00237 unsigned long ipa_PeopleDetector::FaceRecognizer::deleteFaces(std::string label, std::vector<cv::Mat>& face_images, std::vector<cv::Mat>& face_depthmaps)
00238 {
00239         for (int i=0; i<(int)m_face_labels.size(); i++)
00240         {
00241                 if (m_face_labels[i].compare(label) == 0)
00242                 {
00243                         m_face_labels.erase(m_face_labels.begin() + i);
00244                         face_images.erase(face_images.begin() + i);
00245                         i--;
00246                 }
00247         }
00248         return ipa_Utils::RET_OK;
00249 }
00250 
00251 unsigned long ipa_PeopleDetector::FaceRecognizer::deleteFace(int index, std::vector<cv::Mat>& face_images, std::vector<cv::Mat>& face_depthmaps)
00252 {
00253         m_face_labels.erase(m_face_labels.begin() + index);
00254         face_images.erase(face_images.begin() + index);
00255         return ipa_Utils::RET_OK;
00256 }
00257 
00258 unsigned long ipa_PeopleDetector::FaceRecognizer::trainFaceRecognition(ipa_PeopleDetector::FaceRecognizerBaseClass* eff, std::vector<cv::Mat>& data, std::vector<int>& labels)
00259 {
00260 
00261         std::vector<cv::Mat> in_vec;
00262         for (unsigned int i = 0; i < data.size(); i++)
00263         {
00264                 cv::Mat temp = data[i];
00265                 temp.convertTo(temp, CV_64FC1);
00266                 in_vec.push_back(temp);
00267         }
00268 
00269         if (!eff->trainModel(in_vec, labels, m_feature_dim))
00270         {
00271                 std::cout << "[FACEREC] Reognition module could not be initialized !" << std::endl;
00272                 return ipa_Utils::RET_FAILED;
00273         }
00274 
00275         return ipa_Utils::RET_OK;
00276 }
00277 
00278 unsigned long ipa_PeopleDetector::FaceRecognizer::trainRecognitionModel(std::vector<std::string>& identification_labels_to_train)
00279 {
00280         // secure this function with a mutex
00281         boost::lock_guard<boost::mutex> lock(m_data_mutex);
00282 
00283         // load necessary data
00284 
00285         std::vector<cv::Mat> face_images;
00286         unsigned long return_value = loadTrainingData(face_images, identification_labels_to_train);
00287         if (return_value == ipa_Utils::RET_FAILED)
00288                         return ipa_Utils::RET_FAILED;
00289 
00290         m_current_label_set = identification_labels_to_train;
00291 
00292         m_label_num.clear();
00293         for (unsigned int li = 0; li < m_face_labels.size(); li++)
00294         {
00295                 for (unsigned int lj = 0; lj < identification_labels_to_train.size(); lj++)
00296                 {
00297                         if (identification_labels_to_train[lj].compare(m_face_labels[li]) == 0)
00298                                 m_label_num.push_back(lj);
00299                 }
00300         }
00301 
00302         boost::filesystem::path path = m_data_directory;
00303         boost::filesystem::path path_color = path / "rdata_color.xml";
00304 
00305         unsigned long trained = ipa_Utils::RET_FAILED;
00306         if (face_images.size() > 0)
00307         {
00308                 trained = trainFaceRecognition(eff_color, face_images, m_label_num);
00309         }
00310 
00311         saveRecognitionModel();
00312         return trained;
00313 
00314 }
00315 
00316 unsigned long ipa_PeopleDetector::FaceRecognizer::saveRecognitionModel()
00317 {
00318         boost::filesystem::path path = m_data_directory;
00319         boost::filesystem::path complete = path / "rdata_color.xml";
00320 
00321         if (fs::is_directory(path.string()))
00322         {
00323                 if (fs::is_regular_file(complete.string()))
00324                 {
00325                         if (fs::remove(complete.string()) == false)
00326                         {
00327                                 std::cout << "Error: FaceRecognizer::saveRecognitionModel: Cannot remove old recognizer data.\n" << std::endl;
00328                                 return ipa_Utils::RET_FAILED;
00329                         }
00330                 }
00331                 eff_color->saveModel(complete);
00332 
00333                 std::cout << "OPENING at " << complete.string() << std::endl;
00334                 cv::FileStorage fileStorage(complete.string(), cv::FileStorage::APPEND);
00335                 if (!fileStorage.isOpened())
00336                 {
00337                         std::cout << "Error: FaceRecognizer::saveRecognitionModel: Can't save training data.\n" << std::endl;
00338                         return ipa_Utils::RET_FAILED;
00339                 }
00340 
00341                 fileStorage << "string_labels" << "[";
00342                 for (int i = 0; i < m_face_labels.size(); i++)
00343                 {
00344                         fileStorage << m_face_labels[i];
00345                 }
00346                 fileStorage << "]";
00347 
00348                 fileStorage.release();
00349 
00350                 std::cout << "INFO: FaceRecognizer::saveRecognitionModel: recognizer data saved.\n" << std::endl;
00351         }
00352         else
00353         {
00354                 std::cerr << "Error: FaceRecognizer::saveRecognitionModel: Path '" << path << "' is not a directory." << std::endl;
00355                 return ipa_Utils::RET_FAILED;
00356         }
00357 
00358         return ipa_Utils::RET_OK;
00359 }
00360 
00361 unsigned long ipa_PeopleDetector::FaceRecognizer::loadRecognitionModel(std::vector<std::string>& identification_labels_to_recognize)
00362 {
00363         // secure this function with a mutex
00364         boost::lock_guard<boost::mutex>* lock = new boost::lock_guard<boost::mutex>(m_data_mutex);
00365 
00366         // check whether currently trained data set corresponds with intentification_labels_to_recognize
00367         boost::filesystem::path path = m_data_directory;
00368         boost::filesystem::path complete = path / "rdata_color.xml";
00369 
00370         bool training_necessary = false;
00371         std::vector<std::string> temp_face_labels;
00372         if (fs::is_directory(path.string()))
00373         {
00374                 cv::FileStorage fileStorage(complete.string(), cv::FileStorage::READ);
00375                 if (!fileStorage.isOpened())
00376                 {
00377                         std::cout << "Info: FaceRecognizer::loadRecognitionModel: Can't open " << complete.string() << ".\n" << std::endl;
00378                         training_necessary = true;
00379                 }
00380                 else
00381                 {
00382                         // load model labels
00383                         cv::FileNode fn = fileStorage["string_labels"];
00384                         cv::FileNodeIterator it = fn.begin(), it_end = fn.end();
00385                         int idx = 0;
00386                         m_current_label_set.clear();
00387                         for (; it != it_end; ++it, idx++)
00388                         {
00389                                 temp_face_labels.push_back(*it);
00390                                 bool new_label = true;
00391                                 if (idx > 0)
00392                                 {
00393                                         for (int i = 0; i < m_current_label_set.size(); i++)
00394                                         {
00395                                                 if (m_current_label_set[i].compare(*it) == 0)
00396                                                         new_label = false;
00397                                         }
00398                                 }
00399                                 if (new_label)
00400                                         m_current_label_set.push_back(*it);
00401                         }
00402 
00403                         // A vector containing all different labels from the training session exactly once, order of appearance matters! (m_current_label_set[i] stores the corresponding name to the average face coordinates in the face subspace in m_face_class_average_projections.rows(i))
00404                         bool same_data_set = true;
00405                         if (identification_labels_to_recognize.size() == 0 || m_current_label_set.size() != identification_labels_to_recognize.size())
00406                         {
00407                                 same_data_set = false;
00408                         }
00409                         else
00410                         {
00411                                 for (uint i = 0; i < identification_labels_to_recognize.size(); i++)
00412                                 {
00413                                         if (identification_labels_to_recognize[i].compare(m_current_label_set[i]) != 0)
00414                                         {
00415                                                 same_data_set = false;
00416                                                 break;
00417                                         }
00418                                 }
00419                         }
00420 
00421                         if (same_data_set == true)
00422                         {
00423                                 eff_color->loadModel(complete);
00424                                 m_face_labels = temp_face_labels;
00425                                 std::cout << "INFO: FaceRecognizer::loadRecognitionModel: recognizer data loaded.\n" << std::endl;
00426                         }
00427                         else
00428                         {
00429                                 training_necessary = true;
00430                         }
00431 
00432                         fileStorage.release();
00433                         delete lock;
00434                         lock = 0;
00435                 }
00436         }
00437         else
00438         {
00439                 std::cerr << "Error: FaceRecognizer::loadRecognizerData: Path '" << path.string() << "' is not a directory." << std::endl;
00440                 return ipa_Utils::RET_FAILED;
00441         }
00442 
00443         if (training_necessary == true)
00444         {
00445                 // stored set differs from requested set -> recompute the model from training data
00446                 // release lock, trainRecognitionModel requests its own lock
00447                 if (lock != 0)
00448                         delete lock;
00449 
00450                 unsigned long return_value = trainRecognitionModel(identification_labels_to_recognize);
00451                 if (return_value == ipa_Utils::RET_FAILED)
00452                         return ipa_Utils::RET_FAILED;
00453 
00454         }
00455 
00456         if (m_debug == true)
00457         {
00458                 std::cout << "Current model set:" << std::endl;
00459                 for (int i = 0; i < (int)m_current_label_set.size(); i++)
00460                         std::cout << "   - " << m_current_label_set[i] << std::endl;
00461                 std::cout << std::endl;
00462         }
00463 
00464         return ipa_Utils::RET_OK;
00465 }
00466 
00467 unsigned long ipa_PeopleDetector::FaceRecognizer::recognizeFace(cv::Mat& color_image, std::vector<cv::Rect>& face_coordinates, std::vector<std::string>& identification_labels)
00468 {
00469         // secure this function with a mutex
00470         boost::lock_guard<boost::mutex> lock(m_data_mutex);
00471 
00472         if (eff_color->trained_ == false)
00473         {
00474                 std::cout << "Error: FaceRecognizer::recognizeFace: Load or train some identification model, first.\n" << std::endl;
00475                 return ipa_Utils::RET_FAILED;
00476         }
00477 
00478         identification_labels.clear();
00479 
00480         cv::Mat resized_8U1;
00481         cv::Size resized_size(m_eigenvectors[0].size());
00482         for (int i = 0; i < (int)face_coordinates.size(); i++)
00483         {
00484                 cv::Rect face = face_coordinates[i];
00485                 cv::Size norm_size = cv::Size(m_norm_size, m_norm_size);
00486                 convertAndResize(color_image, resized_8U1, face, norm_size);
00487 
00488                 double DFFS;
00489                 resized_8U1.convertTo(resized_8U1, CV_64FC1);
00490 
00491                 cv::Mat coeff_arr;
00492                 //eff_color.projectToSubspace(resized_8U1,coeff_arr,DFFS);
00493 
00494                 if (m_debug)
00495                         std::cout << "distance to face space: " << DFFS << std::endl;
00496                 //TODO temporary turned off
00497                 if (0 == 1)
00498                 {
00499                         // no face
00500                         identification_labels.push_back("No face");
00501                 }
00502                 else
00503                 {
00504 
00505                         int res_label;
00506                         eff_color->classifyImage(resized_8U1, res_label);
00507                         if (res_label == -1)
00508                         {
00509                                 identification_labels.push_back("Unknown Face");
00510                         }
00511                         else
00512                         {
00513                                 identification_labels.push_back(m_current_label_set[res_label]);
00514                         }
00515                 }
00516         }
00517 
00518         return ipa_Utils::RET_OK;
00519 }
00520 
00521 unsigned long ipa_PeopleDetector::FaceRecognizer::recognizeFace(cv::Mat& color_image, cv::Mat& depth_image, std::vector<cv::Rect>& face_coordinates,
00522                 std::vector<std::string>& identification_labels)
00523 {
00524         timeval t1, t2;
00525         gettimeofday(&t1, NULL);
00526         // secure this function with a mutex
00527         boost::lock_guard<boost::mutex> lock(m_data_mutex);
00528 
00529         //int number_eigenvectors = m_eigenvectors.size();
00530         if (eff_color->trained_ == false)
00531         {
00532                 std::cout << "Error: FaceRecognizer::recognizeFace: Load or train some identification model, first.\n" << std::endl;
00533                 return ipa_Utils::RET_FAILED;
00534         }
00535 
00536         identification_labels.clear();
00537 
00538         //cv::Size resized_size(m_eigenvectors[0].size());
00539         for (int i = 0; i < (int)face_coordinates.size(); i++)
00540         {
00541                 cv::Rect face = face_coordinates[i];
00542                 //convertAndResize(depth_image, resized_8U1, face, resized_size);
00543                 cv::Mat color_crop = color_image(face);
00544                 cv::Mat depth_crop_xyz = depth_image(face);
00545 
00546                 cv::Mat DM_crop = cv::Mat::zeros(m_norm_size, m_norm_size, CV_8UC1);
00547                 cv::Size norm_size = cv::Size(m_norm_size, m_norm_size);
00548                 if (face_normalizer_.normalizeFace(color_crop, depth_crop_xyz, norm_size, DM_crop))
00549                         ;
00550 
00551                 double DFFS;
00552                 cv::Mat temp;
00553                 color_crop.convertTo(color_crop, CV_64FC1);
00554 
00555                 int res_label_color, res_label_depth;
00556                 std::string class_color;
00557 
00558                 if (eff_color->trained_)
00559                 {
00560                         eff_color->classifyImage(color_crop, res_label_color);
00561                         if (res_label_color == -1)
00562                         {
00563                                 class_color = "Unknown";
00564                         }
00565                         else
00566                         {
00567                                 class_color = m_current_label_set[res_label_color];
00568                         }
00569                 }
00570 
00571                 identification_labels.push_back(class_color);
00572         }
00573 
00574         gettimeofday(&t2, NULL);
00575         if (m_debug)
00576                 std::cout << "time =" << (t2.tv_usec - t1.tv_usec) / 1000.0 << std::endl;
00577 
00578         return ipa_Utils::RET_OK;
00579 }
00580 
00581 unsigned long ipa_PeopleDetector::FaceRecognizer::convertAndResize(cv::Mat& img, cv::Mat& resized, cv::Rect& face, cv::Size new_size)
00582 {
00583         resized = img(face);
00584         cv::resize(resized, resized, new_size);
00585 
00586         //cv::cvtColor(resized, resized, CV_BGR2GRAY);
00587 
00588         return ipa_Utils::RET_OK;
00589 }
00590 
00591 unsigned long ipa_PeopleDetector::FaceRecognizer::saveTrainingData(std::vector<cv::Mat>& face_images)
00592 {
00593         boost::filesystem::path path = m_data_directory;
00594         boost::filesystem::path complete = path / "tdata.xml";
00595         std::string img_ext = ".bmp";
00596 
00597         if (fs::is_directory(complete))
00598         {
00599                 cv::FileStorage fileStorage(complete.string(), cv::FileStorage::WRITE);
00600                 if (!fileStorage.isOpened())
00601                 {
00602                         std::cout << "Error: FaceRecognizer::saveTrainingData: Can't save training data.\n" << std::endl;
00603                         return ipa_Utils::RET_FAILED;
00604                 }
00605 
00606                 // store data
00607                 fileStorage << "number_entries" << (int)m_face_labels.size();
00608                 for (int i = 0; i < (int)m_face_labels.size(); i++)
00609                 {
00610                         // labels
00611                         std::ostringstream tag;
00612                         tag << "label_" << i;
00613                         fileStorage << tag.str().c_str() << m_face_labels[i].c_str();
00614 
00615                         // face images
00616                         boost::filesystem::path img_path = path / "img" / (boost::lexical_cast<std::string>(i) + img_ext);
00617                         std::ostringstream img, shortname;
00618                         shortname << "img/" << i << img_ext;
00619                         std::ostringstream tag2;
00620                         tag2 << "image_" << i;
00621                         fileStorage << tag2.str().c_str() << shortname.str().c_str();
00622                         cv::imwrite(img_path.string(), face_images[i]);
00623                 }
00624 
00625                 fileStorage.release();
00626 
00627                 std::cout << "INFO: FaceRecognizer::saveTrainingData: " << face_images.size() << " color images saved.\n" << std::endl;
00628         }
00629         else
00630         {
00631                 std::cerr << "Error: FaceRecognizer::saveTrainingData: Path '" << path << "' is not a directory." << std::endl;
00632                 return ipa_Utils::RET_FAILED;
00633         }
00634 
00635         return ipa_Utils::RET_OK;
00636 }
00637 
00638 unsigned long ipa_PeopleDetector::FaceRecognizer::saveTrainingData(std::vector<cv::Mat>& face_images, std::vector<cv::Mat>& face_depthmaps)
00639 {
00640         boost::filesystem::path path = m_data_directory;
00641         boost::filesystem::path complete = path / "tdata.xml";
00642         std::string img_ext = ".bmp";
00643         std::string dm_ext = ".xml";
00644 
00645         if (fs::is_directory(path.string()))
00646         {
00647                 cv::FileStorage fileStorage(complete.string(), cv::FileStorage::WRITE);
00648                 if (!fileStorage.isOpened())
00649                 {
00650                         std::cout << "Error: FaceRecognizer::saveTrainingData: Can't save training data.\n" << std::endl;
00651                         return ipa_Utils::RET_FAILED;
00652                 }
00653 
00654                 // store data
00655                 fileStorage << "number_entries" << (int)m_face_labels.size();
00656                 for (int i = 0; i < (int)m_face_labels.size(); i++)
00657                 {
00658                         // labels
00659                         std::ostringstream tag;
00660                         tag << "label_" << i;
00661                         fileStorage << tag.str().c_str() << m_face_labels[i].c_str();
00662 
00663                         // face images
00664                         boost::filesystem::path img_path = path / "img" / (boost::lexical_cast<std::string>(i) + img_ext);
00665                         std::ostringstream img, shortname_img, shortname_depth;
00666                         shortname_img << "img/" << i << img_ext;
00667                         std::ostringstream tag2, tag3;
00668                         tag2 << "image_" << i;
00669                         fileStorage << tag2.str().c_str() << shortname_img.str().c_str();
00670 
00671                         if (dm_exist[i])
00672                         {
00673                                 shortname_depth << "depth/" << i << dm_ext;
00674                                 tag3 << "depthmap_" << i;
00675                                 fileStorage << tag3.str().c_str() << shortname_depth.str().c_str();
00676                         }
00677                         cv::imwrite(img_path.string(), face_images[i]);
00678                 }
00679 
00680                 fileStorage.release();
00681 
00682                 int j = 0;
00683                 for (unsigned int i = 0; i < dm_exist.size(); i++)
00684                 {
00685                         if (dm_exist[i])
00686                         {
00687                                 // depth maps
00688                                 boost::filesystem::path dm_path = path / "depth" / (boost::lexical_cast<std::string>(i) + ".xml");
00689                                 cv::FileStorage fs(dm_path.string(), FileStorage::WRITE);
00690                                 fs << "depthmap" << face_depthmaps[j];
00691                                 fs.release();
00692                                 j++;
00693                         }
00694                 }
00695                 std::cout << "INFO: FaceRecognizer::saveTrainingData: " << face_images.size() << " color images and " << face_depthmaps.size() << " depth images saved.\n" << std::endl;
00696         }
00697         else
00698         {
00699                 std::cerr << "Error: FaceRecognizer::saveTrainingData: Path '" << path << "' is not a directory." << std::endl;
00700                 return ipa_Utils::RET_FAILED;
00701         }
00702 
00703         return ipa_Utils::RET_OK;
00704 }
00705 
00706 unsigned long ipa_PeopleDetector::FaceRecognizer::loadTrainingData(std::vector<cv::Mat>& face_images, std::vector<std::string>& identification_labels_to_train)
00707 {
00708         bool use_all_data = false;
00709         if (identification_labels_to_train.size() == 0)
00710                 use_all_data = true;
00711 
00712         boost::filesystem::path path = m_data_directory;
00713         boost::filesystem::path complete = path / "tdata.xml";
00714 
00715         if (fs::is_directory(path.string()))
00716         {
00717                 cv::FileStorage fileStorage(complete.string(), cv::FileStorage::READ);
00718                 if (!fileStorage.isOpened())
00719                 {
00720                         std::cout << "Error: FaceRecognizer::loadTrainingData: Can't open " << complete.string() << ".\n" << std::endl;
00721                         return ipa_Utils::RET_FAILED;
00722                 }
00723 
00724                 // labels
00725                 m_face_labels.clear();
00726                 face_images.clear();
00727                 cv::Size norm_size = cv::Size(m_norm_size, m_norm_size);
00728                 int number_entries = (int)fileStorage["number_entries"];
00729                 for (int i = 0; i < number_entries; i++)
00730                 {
00731                         // labels
00732                         std::ostringstream tag_label;
00733                         tag_label << "label_" << i;
00734                         std::string label = (std::string)fileStorage[tag_label.str().c_str()];
00735                         // look up this label in the list of unique labels identification_labels_to_train
00736                         bool class_exists = false;
00737                         for (int j = 0; j < (int)identification_labels_to_train.size(); j++)
00738                         {
00739                                 if (!identification_labels_to_train[j].compare(label))
00740                                         class_exists = true;
00741                         }
00742                         // if it does not appear in the list either append it (use all data option) or neglect this piece of data
00743                         if (class_exists == false)
00744                         {
00745                                 if (use_all_data == true)
00746                                 {
00747                                         // append this label to the list of labels
00748                                         identification_labels_to_train.push_back(label);
00749                                 }
00750                                 else
00751                                 {
00752                                         // skip this data because it does not contain one of the desired labels
00753                                         continue;
00754                                 }
00755                         }
00756                         m_face_labels.push_back(label);
00757 
00758                         // face images
00759                         std::ostringstream tag_image;
00760                         tag_image << "image_" << i;
00761                         boost::filesystem::path path = m_data_directory / (std::string)fileStorage[tag_image.str().c_str()];
00762                         cv::Mat temp = cv::imread(path.string(), -1);
00763                         cv::resize(temp, temp, cv::Size(m_norm_size, m_norm_size));
00764                         //face_normalizer_.normalizeFace(temp,norm_size);
00765                         face_images.push_back(temp);
00766                 }
00767 
00768                 // clean identification_labels_to_train -> only keep those labels that appear in the training data
00769                 for (int j = 0; j < (int)identification_labels_to_train.size(); j++)
00770                 {
00771                         bool class_exists = false;
00772                         for (int k = 0; k < (int)m_face_labels.size(); k++)
00773                         {
00774                                 if (identification_labels_to_train[j].compare(m_face_labels[k]) == 0)
00775                                         class_exists = true;
00776                         }
00777                         if (class_exists == false)
00778                         {
00779                                 identification_labels_to_train.erase(identification_labels_to_train.begin() + j);
00780                                 j--;
00781                         }
00782                 }
00783 
00784                 // set next free filename
00785                 // filename_ = number_face_images;
00786 
00787                 fileStorage.release();
00788 
00789                 std::cout << "INFO: FaceRecognizer::loadTrainingData: " << number_entries << " color images loaded.\n" << std::endl;
00790         }
00791         else
00792         {
00793                 std::cerr << "Error: FaceRecognizer::loadTrainingData: Path '" << path << "' is not a directory." << std::endl;
00794                 return ipa_Utils::RET_FAILED;
00795         }
00796 
00797         return ipa_Utils::RET_OK;
00798 }
00799 
00800 unsigned long ipa_PeopleDetector::FaceRecognizer::loadTrainingData(std::vector<cv::Mat>& face_images, std::vector<cv::Mat>& face_depthmaps,
00801                 std::vector<std::string>& identification_labels_to_train)
00802 {
00803         bool use_all_data = false;
00804         dm_exist.clear();
00805         if (identification_labels_to_train.size() == 0)
00806                 use_all_data = true;
00807 
00808         boost::filesystem::path path = m_data_directory;
00809         boost::filesystem::path complete = path / "tdata.xml";
00810 
00811         if (fs::is_directory(path.string()))
00812         {
00813                 cv::FileStorage fileStorage(complete.string(), cv::FileStorage::READ);
00814                 if (!fileStorage.isOpened())
00815                 {
00816                         std::cout << "Error: FaceRecognizer::loadTrainingData: Can't open " << complete.string() << ".\n" << std::endl;
00817                         return ipa_Utils::RET_FAILED;
00818                 }
00819 
00820                 // labels
00821                 m_face_labels.clear();
00822                 face_images.clear();
00823                 cv::Size norm_size = cv::Size(m_norm_size, m_norm_size);
00824                 int number_entries = (int)fileStorage["number_entries"];
00825                 for (int i = 0; i < number_entries; i++)
00826                 {
00827                         // labels
00828                         std::ostringstream tag_label;
00829                         tag_label << "label_" << i;
00830                         std::string label = (std::string)fileStorage[tag_label.str().c_str()];
00831                         // look up this label in the list of unique labels identification_labels_to_train
00832                         bool class_exists = false;
00833                         for (int j = 0; j < (int)identification_labels_to_train.size(); j++)
00834                         {
00835                                 if (!identification_labels_to_train[j].compare(label))
00836                                         class_exists = true;
00837                         }
00838                         // if it does not appear in the list either append it (use all data option) or neglect this piece of data
00839                         if (class_exists == false)
00840                         {
00841                                 if (use_all_data == true)
00842                                 {
00843                                         // append this label to the list of labels
00844                                         identification_labels_to_train.push_back(label);
00845                                 }
00846                                 else
00847                                 {
00848                                         // skip this data because it does not contain one of the desired labels
00849                                         continue;
00850                                 }
00851                         }
00852                         m_face_labels.push_back(label);
00853 
00854                         // face images
00855                         std::ostringstream tag_image, tag_dm;
00856                         tag_image << "image_" << i;
00857                         tag_dm << "depthmap_" << i;
00858                         boost::filesystem::path img_path = m_data_directory / (std::string)fileStorage[tag_image.str().c_str()];
00859                         boost::filesystem::path dm_path = m_data_directory / (std::string)fileStorage[tag_dm.str().c_str()];
00860                         cv::Mat temp = cv::imread(img_path.string(), -1);
00861 
00862                         if (dm_path.string().compare(m_data_directory.string()))
00863                         {
00864                                 cv::Mat xyz_temp, dm_temp;
00865                                 cv::FileStorage fs(dm_path.string(), FileStorage::READ);
00866                                 fs["depthmap"] >> xyz_temp;
00867                                 face_normalizer_.normalizeFace(temp, xyz_temp, norm_size, dm_temp);
00868                                 face_depthmaps.push_back(dm_temp);
00869                                 dm_exist.push_back(true);
00870                                 fs.release();
00871                         }
00872                         else
00873                         {
00874                                 dm_exist.push_back(false);
00875                         }
00876 
00877                         cv::resize(temp, temp, cv::Size(m_norm_size, m_norm_size));
00878                         face_images.push_back(temp);
00879                 }
00880 
00881                 // clean identification_labels_to_train -> only keep those labels that appear in the training data
00882                 for (int j = 0; j < (int)identification_labels_to_train.size(); j++)
00883                 {
00884                         bool class_exists = false;
00885                         for (int k = 0; k < (int)m_face_labels.size(); k++)
00886                         {
00887                                 if (identification_labels_to_train[j].compare(m_face_labels[k]) == 0)
00888                                         class_exists = true;
00889                         }
00890                         if (class_exists == false)
00891                         {
00892                                 identification_labels_to_train.erase(identification_labels_to_train.begin() + j);
00893                                 j--;
00894                         }
00895                 }
00896 
00897                 // set next free filename
00898                 // filename_ = number_face_images;
00899 
00900                 fileStorage.release();
00901 
00902                 std::cout << "INFO: FaceRecognizer::loadTrainingData: " << number_entries << " images loaded (" << face_images.size() << " color images and " << face_depthmaps.size() << " depth images).\n" << std::endl;
00903         }
00904         else
00905         {
00906                 std::cerr << "Error: FaceRecognizer::loadTrainingData: Path '" << path << "' is not a directory." << std::endl;
00907                 return ipa_Utils::RET_FAILED;
00908         }
00909 
00910         return ipa_Utils::RET_OK;
00911 }
00912 void ipa_PeopleDetector::FaceRecognizer::assertDirectories(boost::filesystem::path& data_directory)
00913 {
00914 
00915         if (!boost::filesystem::exists(data_directory))
00916                 boost::filesystem::create_directories(data_directory);
00917         if (!boost::filesystem::exists(data_directory / "depth"))
00918                 boost::filesystem::create_directories(data_directory / "depth");
00919         if (!boost::filesystem::exists(data_directory / "img"))
00920                 boost::filesystem::create_directories(data_directory / "img");
00921 }


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