faces.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Faces-specific computer vision algorithms.
00003  *
00004  **********************************************************************
00005  *
00006  * Software License Agreement (BSD License)
00007  *
00008  *  Copyright (c) 2008, Willow Garage, Inc.
00009  *  All rights reserved.
00010  *
00011  *  Redistribution and use in source and binary forms, with or without
00012  *  modification, are permitted provided that the following conditions
00013  *  are met:
00014  *
00015  *   * Redistributions of source code must retain the above copyright
00016  *     notice, this list of conditions and the following disclaimer.
00017  *   * Redistributions in binary form must reproduce the above
00018  *     copyright notice, this list of conditions and the following
00019  *     disclaimer in the documentation and/or other materials provided
00020  *     with the distribution.
00021  *   * Neither the name of the Willow Garage nor the names of its
00022  *     contributors may be used to endorse or promote products derived
00023  *     from this software without specific prior written permission.
00024  *
00025  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00026  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00027  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00028  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00029  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00030  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00031  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00032  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00033  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00034  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00035  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00036  *  POSSIBILITY OF SUCH DAMAGE.
00037  *********************************************************************/
00038 
00039 /* Author: Caroline Pantofaru */
00040 
00041 #include "face_detector/faces.h"
00042 #include <cfloat>
00043 #include <algorithm>
00044 
00045 namespace people
00046 {
00047 
00048 Faces::Faces():
00049   list_(NULL),
00050   cam_model_(NULL)
00051 {
00052 }
00053 
00054 Faces::~Faces()
00055 {
00056   // Kill all the threads.
00057   threads_.interrupt_all();
00058   threads_.join_all();
00059   delete face_go_mutex_;
00060   face_go_mutex_ = NULL;
00061 
00062   for (int i = list_.size(); i > 0; i--)
00063   {
00064     list_.pop_back();
00065   }
00066 
00067   cam_model_ = 0;
00068 
00069 }
00070 
00071 
00072 /* Note: The multi-threading in this file is left over from a previous incarnation that allowed multiple
00073  * cascades to be run at once. It hasn't been removed in case we want to return to that model, and since
00074  * there isn't much overhead. Right now, however, only one classifier is being run per instantiation
00075  * of the face_detector node.
00076  */
00077 
00078 
00079 void Faces::initFaceDetectionDisparity(uint num_cascades, string haar_classifier_filename, double face_size_min_m, double face_size_max_m, double max_face_z_m, double face_sep_dist_m)
00080 {
00081   images_ready_ = 0;
00082 
00083   face_size_min_m_ = face_size_min_m;
00084   face_size_max_m_ = face_size_max_m;
00085   max_face_z_m_ = max_face_z_m;
00086   face_sep_dist_m_ = face_sep_dist_m;
00087 
00088   face_go_mutex_ = new boost::mutex();
00089   bool cascade_ok = cascade_.load(haar_classifier_filename);
00090 
00091   if (!cascade_ok)
00092   {
00093     ROS_ERROR_STREAM("Cascade file " << haar_classifier_filename << " doesn't exist.");
00094     return;
00095   }
00096   threads_.create_thread(boost::bind(&Faces::faceDetectionThreadDisparity, this, 0));
00097 }
00098 
00100 
00101 vector<Box2D3D> Faces::detectAllFacesDisparity(const cv::Mat &image, double threshold, const cv::Mat &disparity_image, image_geometry::StereoCameraModel *cam_model)
00102 {
00103 
00104   faces_.clear();
00105 
00106   // Convert the image to grayscale, if necessary.
00107 
00108   if (image.channels() == 1)
00109   {
00110     cv_image_gray_.create(image.size(), CV_8UC1);
00111     image.copyTo(cv_image_gray_);
00112   }
00113   else if (image.channels() == 3)
00114   {
00115     cv_image_gray_.create(image.size(), CV_8UC1);
00116     cv::cvtColor(image, cv_image_gray_, CV_BGR2GRAY);
00117   }
00118   else
00119   {
00120     std::cerr << "Unknown image type" << std::endl;
00121     return faces_;
00122   }
00123 
00124   disparity_image_ = &disparity_image;
00125   cam_model_ = cam_model;
00126 
00127   // Tell the face detection threads that they can run once.
00128   num_threads_to_wait_for_ = threads_.size();
00129   boost::mutex::scoped_lock fgmlock(*(face_go_mutex_));
00130   images_ready_++;
00131   fgmlock.unlock();
00132 
00133   face_detection_ready_cond_.notify_all();
00134 
00135   boost::mutex::scoped_lock fdmlock(face_done_mutex_);
00136   while (num_threads_to_wait_for_ > 0)
00137   {
00138     face_detection_done_cond_.wait(fdmlock);
00139   }
00140 
00141   return faces_;
00142 }
00143 
00145 
00146 void Faces::faceDetectionThreadDisparity(uint i)
00147 {
00148 
00149   while (1)
00150   {
00151     boost::mutex::scoped_lock fgmlock(*(face_go_mutex_));
00152     boost::mutex::scoped_lock tlock(t_mutex_, boost::defer_lock);
00153     while (1)
00154     {
00155       tlock.lock();
00156       if (images_ready_)
00157       {
00158         --images_ready_;
00159         tlock.unlock();
00160         break;
00161       }
00162       tlock.unlock();
00163       face_detection_ready_cond_.wait(fgmlock);
00164     }
00165 
00166     // Find the faces using OpenCV's haar cascade object detector.
00167     cv::Point3d p3_1(0, 0, max_face_z_m_);
00168     cv::Point3d p3_2(face_size_min_m_, 0, max_face_z_m_);
00169     cv::Point2d p2_1 = (cam_model_->left()).project3dToPixel(p3_1);
00170     cv::Point2d p2_2 = (cam_model_->left()).project3dToPixel(p3_2);
00171     int this_min_face_size = (int)(floor(fabs(p2_2.x - p2_1.x)));
00172 
00173     std::vector<cv::Rect> faces_vec;
00174     cascade_.detectMultiScale(cv_image_gray_, faces_vec,  1.2, 2, CV_HAAR_DO_CANNY_PRUNING, cv::Size(this_min_face_size, this_min_face_size));
00175 
00176     // Filter the faces using depth information, if available. Currently checks that the actual face size is within the given limits.
00177     cv::Scalar color(0, 255, 0);
00178     Box2D3D one_face;
00179     double avg_disp = 0.0;
00180     cv::Mat uvd(1, 3, CV_32FC1);
00181     cv::Mat xyz(1, 3, CV_32FC1);
00182     // For each face...
00183     for (uint iface = 0; iface < faces_vec.size(); iface++)  //face_seq->total; iface++) {
00184     {
00185 
00186       one_face.status = "good";
00187 
00188       one_face.box2d = faces_vec[iface];
00189       one_face.id = i; // The cascade that computed this face.
00190 
00191       // Get the median disparity in the middle half of the bounding box.
00192       cv::Mat disp_roi_shallow(*disparity_image_, cv::Rect(floor(one_face.box2d.x + 0.25 * one_face.box2d.width),
00193                                floor(one_face.box2d.y + 0.25 * one_face.box2d.height),
00194                                floor(one_face.box2d.x + 0.75 * one_face.box2d.width) - floor(one_face.box2d.x + 0.25 * one_face.box2d.width) + 1,
00195                                floor(one_face.box2d.y + 0.75 * one_face.box2d.height) - floor(one_face.box2d.y + 0.25 * one_face.box2d.height) + 1));
00196       cv::Mat disp_roi = disp_roi_shallow.clone();
00197       cv::Mat tmat = disp_roi.reshape(1, disp_roi.rows * disp_roi.cols);
00198       cv::Mat tmat_sorted;
00199       cv::sort(tmat, tmat_sorted, CV_SORT_EVERY_COLUMN + CV_SORT_DESCENDING);
00200       avg_disp = tmat_sorted.at<float>(floor(cv::countNonZero(tmat_sorted >= 0.0) / 2.0)); // Get the middle valid disparity (-1 disparities are invalid)
00201 
00202       // Fill in the rest of the face data structure.
00203       one_face.center2d = cv::Point2d(one_face.box2d.x + one_face.box2d.width / 2.0,
00204                                       one_face.box2d.y + one_face.box2d.height / 2.0);
00205       one_face.width2d = one_face.box2d.width;
00206 
00207       // If the median disparity was valid and the face is a reasonable size, the face status is "good".
00208       // If the median disparity was valid but the face isn't a reasonable size, the face status is "bad".
00209       // Otherwise, the face status is "unknown".
00210       if (avg_disp > 0)
00211       {
00212         cam_model_->projectDisparityTo3d(cv::Point2d(0.0, 0.0), avg_disp, p3_1);
00213         cam_model_->projectDisparityTo3d(cv::Point2d(one_face.box2d.width, 0.0), avg_disp, p3_2);
00214         one_face.width3d = fabs(p3_2.x - p3_1.x);
00215         cam_model_->projectDisparityTo3d(one_face.center2d, avg_disp, one_face.center3d);
00216         if (one_face.center3d.z > max_face_z_m_ || one_face.width3d < face_size_min_m_ || one_face.width3d > face_size_max_m_)
00217         {
00218           one_face.status = "bad";
00219         }
00220       }
00221       else
00222       {
00223         one_face.width3d = 0.0;
00224         one_face.center3d = cv::Point3d(0.0, 0.0, 0.0);
00225         one_face.status = "unknown";
00226       }
00227 
00228       // Add faces to the output vector.
00229       // lock faces
00230       boost::mutex::scoped_lock lock(face_mutex_);
00231       faces_.push_back(one_face);
00232       lock.unlock();
00233     }
00234 
00235     boost::mutex::scoped_lock fdmlock(face_done_mutex_);
00236     num_threads_to_wait_for_--;
00237     fdmlock.unlock();
00238     face_detection_done_cond_.notify_one();
00239   }
00240 }
00241 
00243 
00244 void Faces::initFaceDetectionDepth(uint num_cascades, string haar_classifier_filename, double face_size_min_m, double face_size_max_m, double max_face_z_m, double face_sep_dist_m)
00245 {
00246 
00247   images_ready_ = 0;
00248 
00249   face_size_min_m_ = face_size_min_m;
00250   face_size_max_m_ = face_size_max_m;
00251   max_face_z_m_ = max_face_z_m;
00252   face_sep_dist_m_ = face_sep_dist_m;
00253 
00254   face_go_mutex_ = new boost::mutex();
00255   bool cascade_ok = cascade_.load(haar_classifier_filename);
00256 
00257   if (!cascade_ok)
00258   {
00259     ROS_ERROR_STREAM("Cascade file " << haar_classifier_filename << " doesn't exist.");
00260     return;
00261   }
00262   threads_.create_thread(boost::bind(&Faces::faceDetectionThreadDepth, this, 0));
00263 }
00264 
00265 
00267 
00268 vector<Box2D3D> Faces::detectAllFacesDepth(const cv::Mat &image, double threshold, const cv::Mat &dimage, image_geometry::StereoCameraModel *cam_model)
00269 {
00270 
00271   faces_.clear();
00272 
00273   // Convert the image to grayscale, if necessary.
00274 
00275   if (image.channels() == 1)
00276   {
00277     cv_image_gray_.create(image.size(), CV_8UC1);
00278     image.copyTo(cv_image_gray_);
00279   }
00280   else if (image.channels() == 3)
00281   {
00282     cv_image_gray_.create(image.size(), CV_8UC1);
00283     cv::cvtColor(image, cv_image_gray_, CV_BGR2GRAY);
00284   }
00285   else
00286   {
00287     std::cerr << "Unknown image type" << std::endl;
00288     return faces_;
00289   }
00290 
00291   depth_image_ = &dimage;
00292   cam_model_ = cam_model;
00293 
00294   // Tell the face detection threads that they can run once.
00295   num_threads_to_wait_for_ = threads_.size();
00296   boost::mutex::scoped_lock fgmlock(*(face_go_mutex_));
00297   images_ready_++;
00298   fgmlock.unlock();
00299 
00300   face_detection_ready_cond_.notify_all();
00301 
00302   boost::mutex::scoped_lock fdmlock(face_done_mutex_);
00303   while (num_threads_to_wait_for_ > 0)
00304   {
00305     face_detection_done_cond_.wait(fdmlock);
00306   }
00307 
00308   return faces_;
00309 }
00310 
00312 
00313 void Faces::faceDetectionThreadDepth(uint i)
00314 {
00315 
00316   while (1)
00317   {
00318     boost::mutex::scoped_lock fgmlock(*(face_go_mutex_));
00319     boost::mutex::scoped_lock tlock(t_mutex_, boost::defer_lock);
00320     while (1)
00321     {
00322       tlock.lock();
00323       if (images_ready_)
00324       {
00325         --images_ready_;
00326         tlock.unlock();
00327         break;
00328       }
00329       tlock.unlock();
00330       face_detection_ready_cond_.wait(fgmlock);
00331     }
00332 
00333     // Find the faces using OpenCV's haar cascade object detector.
00334     cv::Point3d p3_1(0, 0, max_face_z_m_);
00335     cv::Point3d p3_2(face_size_min_m_, 0, max_face_z_m_);
00336     cv::Point2d p2_1 = (cam_model_->left()).project3dToPixel(p3_1);
00337     cv::Point2d p2_2 = (cam_model_->left()).project3dToPixel(p3_2);
00338     int this_min_face_size = (int)(floor(fabs(p2_2.x - p2_1.x)));
00339 
00340     std::vector<cv::Rect> faces_vec;
00341     cascade_.detectMultiScale(cv_image_gray_, faces_vec,  1.2, 2, CV_HAAR_DO_CANNY_PRUNING, cv::Size(this_min_face_size, this_min_face_size));
00342 
00343     // Filter the faces using depth information, if available. Currently checks that the actual face size is within the given limits.
00344     cv::Scalar color(0, 255, 0);
00345     Box2D3D one_face;
00346     double avg_d = 0.0;
00347     cv::Mat uvd(1, 3, CV_32FC1);
00348     cv::Mat xyz(1, 3, CV_32FC1);
00349     // For each face...
00350     for (uint iface = 0; iface < faces_vec.size(); iface++)
00351     {
00352 
00353       one_face.status = "good";
00354 
00355       one_face.box2d = faces_vec[iface];
00356       one_face.id = i; // The cascade that computed this face.
00357 
00358       // Get the median depth in the middle half of the bounding box.
00359       cv::Mat depth_roi_shallow(*depth_image_, cv::Rect(floor(one_face.box2d.x + 0.25 * one_face.box2d.width),
00360                                 floor(one_face.box2d.y + 0.25 * one_face.box2d.height),
00361                                 floor(one_face.box2d.x + 0.75 * one_face.box2d.width) - floor(one_face.box2d.x + 0.25 * one_face.box2d.width) + 1,
00362                                 floor(one_face.box2d.y + 0.75 * one_face.box2d.height) - floor(one_face.box2d.y + 0.25 * one_face.box2d.height) + 1));
00363 
00364       // Fill in the rest of the face data structure.
00365       one_face.center2d = cv::Point2d(one_face.box2d.x + one_face.box2d.width / 2.0,
00366                                       one_face.box2d.y + one_face.box2d.height / 2.0);
00367       one_face.width2d = one_face.box2d.width;
00368 
00369 
00370       // If the median depth was valid and the face is a reasonable size, the face status is "good".
00371       // If the median depth was valid but the face isn't a reasonable size, the face status is "bad".
00372       // Otherwise, the face status is "unknown".
00373 
00374       std::vector<float> depths;
00375       // Copy the depths removing the nans.
00376       for (int i = 0; i < depth_roi_shallow.rows; i++)
00377       {
00378         const float* dptr = depth_roi_shallow.ptr<float>(i);
00379         for (int j = 0; j < depth_roi_shallow.cols; j++)
00380         {
00381           if (dptr[j] == dptr[j])
00382           {
00383             depths.push_back(dptr[j]);
00384           }
00385         }
00386       }
00387 
00388       std::vector<float>::iterator dbegin = depths.begin();
00389       std::vector<float>::iterator dend = depths.end();
00390 
00391       if (depths.size() > 0)
00392       {
00393         std::sort(dbegin, dend);
00394         avg_d = depths[floor(depths.size() / 2.0)];
00395 
00396         one_face.width3d = fabs((cam_model_->left()).getDeltaX(one_face.box2d.width, avg_d));
00397         one_face.center3d = (cam_model_->left()).projectPixelTo3dRay(one_face.center2d);
00398 
00399         one_face.center3d = (avg_d / one_face.center3d.z) * one_face.center3d;
00400         if (one_face.center3d.z > max_face_z_m_ || one_face.width3d < face_size_min_m_ || one_face.width3d > face_size_max_m_)
00401         {
00402           one_face.status = "bad";
00403         }
00404       }
00405       else
00406       {
00407         one_face.width3d = 0.0;
00408         one_face.center3d = cv::Point3d(0.0, 0.0, 0.0);
00409         one_face.status = "unknown";
00410       }
00411 
00412       // Add faces to the output vector.
00413       // lock faces
00414       boost::mutex::scoped_lock lock(face_mutex_);
00415       faces_.push_back(one_face);
00416       lock.unlock();
00417     }
00418 
00419     boost::mutex::scoped_lock fdmlock(face_done_mutex_);
00420     num_threads_to_wait_for_--;
00421     fdmlock.unlock();
00422     face_detection_done_cond_.notify_one();
00423   }
00424 
00425 }
00426 
00427 };


face_detector
Author(s): Caroline Pantofaru
autogenerated on Sat Jun 8 2019 18:40:20