face_detector.cpp
Go to the documentation of this file.
00001 
00061 #ifdef __LINUX__
00062         #include "cob_people_detection/face_detector.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 #include <opencv/cv.h>
00070 #include <opencv/cvaux.h>
00071 #include <opencv/highgui.h>
00072 
00073 using namespace ipa_PeopleDetector;
00074 
00075 FaceDetector::FaceDetector(void)
00076 {       
00077         m_face_cascade = 0;
00078         m_initialized = false;
00079 }
00080 
00081 unsigned long FaceDetector::init(std::string directory, double faces_increase_search_scale, int faces_drop_groups, int faces_min_search_scale_x, int faces_min_search_scale_y,
00082                 bool reason_about_3dface_size, double face_size_max_m, double face_size_min_m, double max_face_z_m, bool debug)
00083 {
00084         // parameters
00085         m_faces_increase_search_scale = faces_increase_search_scale;
00086         m_faces_drop_groups = faces_drop_groups;
00087         m_faces_min_search_scale_x = faces_min_search_scale_x;
00088         m_faces_min_search_scale_y = faces_min_search_scale_y;
00089         m_reason_about_3dface_size = reason_about_3dface_size;
00090         m_face_size_max_m = face_size_max_m;
00091         m_face_size_min_m = face_size_min_m;
00092         m_max_face_z_m = max_face_z_m;
00093         m_debug = debug;
00094 
00095         // load Haar-Classifier for frontal face detection
00096         std::string faceCascadePath = directory + "haarcascades/haarcascade_frontalface_alt2.xml";
00097         m_face_cascade = (CvHaarClassifierCascade*)cvLoad(faceCascadePath.c_str(), 0, 0, 0 );   //"ConfigurationFiles/haarcascades/haarcascade_frontalface_alt2.xml", 0, 0, 0 );
00098 
00099         // Create Memory
00100         m_storage = cvCreateMemStorage(0);
00101 
00102         m_initialized = true;
00103 
00104         return ipa_Utils::RET_OK;
00105 }
00106 
00107 FaceDetector::~FaceDetector(void)
00108 {
00109         // Release Classifiers and memory
00110         cvReleaseHaarClassifierCascade(&m_face_cascade);
00111         cvReleaseMemStorage(&m_storage);
00112 }
00113 
00114 unsigned long FaceDetector::detectColorFaces(std::vector<cv::Mat>& heads_color_images, const std::vector<cv::Mat>& heads_depth_images, std::vector<std::vector<cv::Rect> >& face_coordinates)
00115 {
00116         if (m_initialized == false)
00117         {
00118                 std::cout << "Error: FaceDetector::DetectColorFaces: init() must be called first." << std::endl;
00119                 return ipa_Utils::RET_FAILED;
00120         }
00121 
00122         face_coordinates.clear();
00123         face_coordinates.resize(heads_color_images.size());
00124 
00125         // iterate over head regions
00126         for(unsigned int head=0; head<heads_color_images.size(); head++)
00127         {
00128                 // detect faces in color image in proposed region
00129                 IplImage imgPtr = (IplImage)heads_color_images[head];
00130                 CvSeq* faces = cvHaarDetectObjects(&imgPtr,     m_face_cascade, m_storage, m_faces_increase_search_scale, m_faces_drop_groups, CV_HAAR_DO_CANNY_PRUNING, cvSize(m_faces_min_search_scale_x, m_faces_min_search_scale_y));
00131 
00132                 cv::Size parentSize;
00133                 cv::Point roiOffset;
00134                 for(int i=0; i<faces->total; i++)
00135                 {
00136                         cv::Rect* face = (cv::Rect*)cvGetSeqElem(faces, i);
00137 //                      heads_color_images[head].locateROI(parentSize, roiOffset);
00138 //                      face->x += roiOffset.x;         // todo: check what happens if the original matrix is used without roi
00139 //                      face->y += roiOffset.y;
00140                         // exclude faces that are too small for the head bounding box
00141                         if (face->width > 0.4*heads_color_images[head].cols && face->height > 0.4*heads_color_images[head].rows)
00142                                 face_coordinates[head].push_back(*face);
00143                 }
00144         }
00145 
00146         if (m_reason_about_3dface_size==true)
00147         {
00148                 // check whether the color faces have a reasonable 3D size
00149                 for (uint head_index=0; head_index<face_coordinates.size(); head_index++)
00150                 {
00151                         double avg_depth_value = 0.0;
00152                         int last_accepted_face_index = -1;
00153                         double last_accepted_face_area = 0.0;
00154                         for (uint face_index = 0; face_index < face_coordinates[head_index].size(); face_index++)
00155                         {
00156                                 //std::cout << face_index << ": face_coordinates[head_index].size()=" << face_coordinates[head_index].size() << std::endl;
00157 
00158                                 cv::Rect& face = face_coordinates[head_index][face_index];
00159 
00160                                 // Get the median disparity in the middle half of the bounding box.
00161                                 int uStart = floor(0.25*face.width);
00162                                 int uEnd = floor(0.75*face.width) + 1;
00163                                 int vStart = floor(0.25*face.height);
00164                                 int vEnd = floor(0.75*face.height) + 1;
00165                                 int du = abs(uEnd-uStart);
00166 
00167                                 // generate vector of all depth values in the face region, NaNs are converted to -1
00168                                 cv::Mat face_region = heads_depth_images[head_index];
00169         // EDIT
00170                                 cv::Mat tmat(1, du*abs(vEnd-vStart), CV_32FC1);
00171                                 float* tmatPtr = (float*)tmat.data;
00172                                 for (int v=vStart; v<vEnd; v++)
00173                                 {
00174                                         float* zPtr = (float*)face_region.row(v).data;
00175                                         zPtr += 2+3*uStart;
00176                                         for (int u=uStart; u<uEnd; u++)
00177                                         {
00178                                                 float depthval = *zPtr;
00179                                                 if (!isnan(depthval)) *tmatPtr = depthval;
00180                                                 else *tmatPtr = -1.0;
00181                                                 tmatPtr++;
00182                                                 zPtr += 3;
00183                                         }
00184                                 }
00185 
00186                                 // median
00187                                 cv::Mat tmat_sorted;
00188                                 cv::sort(tmat, tmat_sorted, CV_SORT_EVERY_ROW+CV_SORT_DESCENDING);
00189                                 double avg_depth = tmat_sorted.at<float>(floor(cv::countNonZero(tmat_sorted>=0.0)*0.5)); // Get the middle valid disparity (-1 disparities are invalid)
00190 
00191                                 // If the median disparity was valid and the face is a reasonable size, the face status is "good".
00192                                 // If the median disparity was valid but the face isn't a reasonable size, the face status is "bad".
00193                                 // Otherwise, the face status is "unknown".
00194                                 // Only bad faces are removed
00195                                 bool remove_face = false;
00196                                 if (avg_depth > 0)
00197                                 {
00198                                         double radiusX, radiusY, radius3d=1e20;
00199                                         cv::Vec3f a, b;
00200                                         // vertical line regularly lies completely on the head whereas this does not hold very often for the horizontal line crossing the bounding box of the face
00201                                         // rectangle in the middle
00202                                         a = heads_depth_images[head_index].at<cv::Vec3f>((int)(face.y+face.height*0.25), (int)(face.x+0.5*face.width));
00203                                         b = heads_depth_images[head_index].at<cv::Vec3f>((int)(face.y+face.height*0.75), (int)(face.x+0.5*face.width));
00204                                         if (m_debug) std::cout << "a: " << a.val[0] << " " << a.val[1] << " " << a.val[2] << "   b: " << " " << b.val[0] << " " << b.val[1] << " " << b.val[2] << "\n";
00205                                         if (isnan(a.val[0]) || isnan(b.val[0])) radiusY = 0.0;
00206                                         else radiusY = cv::norm(b-a);
00207                                         radius3d = radiusY;
00208 
00209                                         // for radius estimation with the horizontal line through the face rectangle use points which typically still lie on the face and not in the background
00210                                         a = heads_depth_images[head_index].at<cv::Vec3f>((int)(face.y+face.height*0.5), (int)(face.x+face.width*0.25));
00211                                         b = heads_depth_images[head_index].at<cv::Vec3f>((int)(face.y+face.height*0.5), (int)(face.x+face.width*0.75));
00212                                         if (m_debug) std::cout << "a: " << a.val[0] << " " << a.val[1] << " " << a.val[2] << "   b: " << " " << b.val[0] << " " << b.val[1] << " " << b.val[2] << "\n";
00213                                         if (isnan(a.val[0]) || isnan(b.val[0])) radiusX = 0.0;
00214                                         else
00215                                         {
00216                                                 radiusX = cv::norm(b-a);
00217                                                 if (radiusY != 0.0) radius3d = (radiusX+radiusY)*0.5;
00218                                                 else radius3d = radiusX;
00219                                         }
00220 
00221 //                                      cv::Point pup(face.x+0.5*face.width, face.y+face.height*0.25);
00222 //                                      cv::Point plo(face.x+0.5*face.width, face.y+face.height*0.75);
00223 //                                      cv::Point ple(face.x+face.width*0.25, face.y+face.height*0.5);
00224 //                                      cv::Point pri(face.x+face.width*0.75, face.y+face.height*0.5);
00225 //                                      cv::line(xyz_image_8U3, pup, plo, CV_RGB(255, 255, 255), 2);
00226 //                                      cv::line(xyz_image_8U3, ple, pri, CV_RGB(255, 255, 255), 2);
00227 
00228                                         if (m_debug)
00229                                         {
00230                                                 std::cout << "radiusX: " << radiusX << "  radiusY: " << radiusY << "\n";
00231                                                 std::cout << "avg_depth: " << avg_depth << " > max_face_z_m: " << m_max_face_z_m << " ?  2*radius3d: " << 2.0*radius3d << " < face_size_min_m: " << m_face_size_min_m << " ?  2radius3d: " << 2.0*radius3d << " > face_size_max_m:" << m_face_size_max_m << "?\n";
00232                                         }
00233                                         if (radius3d > 0.0 && (avg_depth > m_max_face_z_m || 2.0*radius3d < m_face_size_min_m || 2.0*radius3d > m_face_size_max_m))
00234                                         {
00235                                                 remove_face = true;
00236                                         }
00237                                 }
00238 
00239                                 if (remove_face==true)
00240                                 {
00241                                         // face does not match normal human appearance -> remove from list
00242                                         face_coordinates[head_index].erase(face_coordinates[head_index].begin()+face_index);
00243                                         face_index--;
00244                                 }
00245                                 else
00246                                 {
00247                                         // only one face can be detected per head -> check which has the bigger face area in the image
00248                                         double current_area = face_coordinates[head_index][face_index].height * face_coordinates[head_index][face_index].width;
00249                                         if (last_accepted_face_index == -1)
00250                                         {
00251                                                 last_accepted_face_index = (int)face_index;
00252                                                 last_accepted_face_area = current_area;
00253                                                 avg_depth_value = avg_depth;
00254                                         }
00255                                         else
00256                                         {
00257                                                 if (current_area > last_accepted_face_area)
00258                                                 {
00259                                                         // delete old selection
00260                                                         face_coordinates[head_index].erase(face_coordinates[head_index].begin()+last_accepted_face_index);
00261                                                         face_index--;
00262 
00263                                                         last_accepted_face_index = face_index;
00264                                                         last_accepted_face_area = current_area;
00265                                                         avg_depth_value = avg_depth;
00266                                                 }
00267                                                 else
00268                                                 {
00269                                                         // delete current face
00270                                                         face_coordinates[head_index].erase(face_coordinates[head_index].begin()+face_index);
00271                                                         face_index--;
00272                                                 }
00273                                         }
00274                                 }
00275                         }
00276                         assert(face_coordinates[head_index].size()==0 || face_coordinates[head_index].size()==1);
00277 
00278                         // clear image background
00279                         if (avg_depth_value > 0)
00280                                 for (int v=0; v<heads_depth_images[head_index].rows; v++)
00281                                         for (int u=0; u<heads_depth_images[head_index].cols; u++)
00282                                         {
00283                                                 float val = heads_depth_images[head_index].at<cv::Vec3f>(v,u)[2];
00284                                                 if (val==0.f || fabs(heads_depth_images[head_index].at<cv::Vec3f>(v,u)[2]-avg_depth_value) > 0.18 || val!=val)
00285                                                         heads_color_images[head_index].at<cv::Vec3b>(v,u) = cv::Vec3b(255, 255, 255);
00286                                         }
00287 //                      std::cout << "avg_depth_value=" << avg_depth_value << std::endl;
00288 //                      cv::imshow("rgb image", heads_color_images[head_index]);
00289 //                      cv::waitKey(10);
00290 //                      cv::imshow("xyz image", xyz_image_8U3);
00291 //                      cv::waitKey(10);
00292                 }
00293         }
00294 
00295         return ipa_Utils::RET_OK;
00296 }
00297 


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