00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041 #include "face_detector/faces.h"
00042 #include <cfloat>
00043
00044 namespace people {
00045
00046 Faces::Faces():
00047 list_(NULL),
00048 cam_model_(NULL) {
00049 }
00050
00051 Faces::~Faces() {
00052
00053 threads_.interrupt_all();
00054 threads_.join_all();
00055 delete face_go_mutex_;
00056 face_go_mutex_ = NULL;
00057
00058 for (int i=list_.size(); i>0; i--) {
00059 list_.pop_back();
00060 }
00061
00062 cam_model_ = 0;
00063
00064 }
00065
00066
00067
00068
00069
00070
00071
00072
00073
00074 void Faces::initFaceDetection(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) {
00075 images_ready_ = 0;
00076
00077 face_size_min_m_ = face_size_min_m;
00078 face_size_max_m_ = face_size_max_m;
00079 max_face_z_m_ = max_face_z_m;
00080 face_sep_dist_m_ = face_sep_dist_m;
00081
00082 face_go_mutex_ = new boost::mutex();
00083 bool cascade_ok = cascade_.load(haar_classifier_filename);
00084
00085 if (!cascade_ok) {
00086 ROS_ERROR_STREAM("Cascade file " << haar_classifier_filename << " doesn't exist.");
00087 return;
00088 }
00089 threads_.create_thread(boost::bind(&Faces::faceDetectionThread,this,0));
00090 }
00091
00093
00094 vector<Box2D3D> Faces::detectAllFaces(cv::Mat &image, double threshold, cv::Mat &disparity_image, image_geometry::StereoCameraModel *cam_model) {
00095
00096 faces_.clear();
00097
00098
00099
00100 if (image.channels() == 1) {
00101 cv_image_gray_.create(image.size(), CV_8UC1);
00102 image.copyTo(cv_image_gray_);
00103 }
00104 else if (image.channels() == 3) {
00105 cv_image_gray_.create(image.size(), CV_8UC1);
00106 cv::cvtColor(image, cv_image_gray_, CV_BGR2GRAY);
00107 }
00108 else {
00109 std::cerr << "Unknown image type"<<std::endl;
00110 return faces_;
00111 }
00112
00113 disparity_image_ = &disparity_image;
00114 cam_model_ = cam_model;
00115
00116
00117 num_threads_to_wait_for_ = threads_.size();
00118 boost::mutex::scoped_lock fgmlock(*(face_go_mutex_));
00119 images_ready_++;
00120 fgmlock.unlock();
00121
00122 face_detection_ready_cond_.notify_all();
00123
00124 boost::mutex::scoped_lock fdmlock(face_done_mutex_);
00125 while (num_threads_to_wait_for_ > 0) {
00126 face_detection_done_cond_.wait(fdmlock);
00127 }
00128
00129 return faces_;
00130 }
00131
00133
00134 void Faces::faceDetectionThread(uint i) {
00135
00136 while (1) {
00137 boost::mutex::scoped_lock fgmlock(*(face_go_mutex_));
00138 boost::mutex::scoped_lock tlock(t_mutex_, boost::defer_lock);
00139 while (1) {
00140 tlock.lock();
00141 if (images_ready_) {
00142 --images_ready_;
00143 tlock.unlock();
00144 break;
00145 }
00146 tlock.unlock();
00147 face_detection_ready_cond_.wait(fgmlock);
00148 }
00149
00150
00151 cv::Point3d p3_1(0,0,max_face_z_m_);
00152 cv::Point3d p3_2(face_size_min_m_,0,max_face_z_m_);
00153 cv::Point2d p2_1, p2_2;
00154 (cam_model_->left()).project3dToPixel(p3_1,p2_1);
00155 (cam_model_->left()).project3dToPixel(p3_2,p2_2);
00156 int this_min_face_size = (int)(floor(fabs(p2_2.x-p2_1.x)));
00157
00158 std::vector<cv::Rect> faces_vec;
00159 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));
00160
00161
00162 cv::Scalar color(0,255,0);
00163 Box2D3D one_face;
00164 double avg_disp = 0.0;
00165 cv::Mat uvd(1,3,CV_32FC1);
00166 cv::Mat xyz(1,3,CV_32FC1);
00167
00168 for (uint iface = 0; iface < faces_vec.size(); iface++) {
00169
00170 one_face.status = "good";
00171
00172 one_face.box2d = faces_vec[iface];
00173 one_face.id = i;
00174
00175
00176 cv::Mat disp_roi_shallow(*disparity_image_,cv::Rect(floor(one_face.box2d.x+0.25*one_face.box2d.width),
00177 floor(one_face.box2d.y+0.25*one_face.box2d.height),
00178 floor(one_face.box2d.x+0.75*one_face.box2d.width) - floor(one_face.box2d.x+0.25*one_face.box2d.width) + 1,
00179 floor(one_face.box2d.y+0.75*one_face.box2d.height) - floor(one_face.box2d.y+0.25*one_face.box2d.height) + 1));
00180 cv::Mat disp_roi = disp_roi_shallow.clone();
00181 cv::Mat tmat = disp_roi.reshape(1,disp_roi.rows*disp_roi.cols);
00182 cv::Mat tmat_sorted;
00183 cv::sort(tmat, tmat_sorted, CV_SORT_EVERY_COLUMN+CV_SORT_DESCENDING);
00184 avg_disp = tmat_sorted.at<float>(floor(cv::countNonZero(tmat_sorted>=0.0)/2.0));
00185
00186
00187 one_face.center2d = cv::Point2d(one_face.box2d.x+one_face.box2d.width/2.0,
00188 one_face.box2d.y+one_face.box2d.height/2.0);
00189 one_face.radius2d = one_face.box2d.width/2.0;
00190
00191
00192
00193
00194 if (avg_disp > 0) {
00195 cam_model_->projectDisparityTo3d(cv::Point2d(0.0,0.0),avg_disp,p3_1);
00196 cam_model_->projectDisparityTo3d(cv::Point2d(one_face.box2d.width,0.0),avg_disp,p3_2);
00197 one_face.radius3d = fabs(p3_2.x-p3_1.x)/2.0;
00198 cam_model_->projectDisparityTo3d(one_face.center2d, avg_disp, one_face.center3d);
00199 if (one_face.center3d.z > max_face_z_m_ || 2.0*one_face.radius3d < face_size_min_m_ || 2.0*one_face.radius3d > face_size_max_m_) {
00200 one_face.status = "bad";
00201 }
00202 }
00203 else {
00204 one_face.radius3d = 0.0;
00205 one_face.center3d = cv::Point3d(0.0,0.0,0.0);
00206 one_face.status = "unknown";
00207 }
00208
00209
00210
00211 boost::mutex::scoped_lock lock(face_mutex_);
00212 faces_.push_back(one_face);
00213 lock.unlock();
00214 }
00215
00216 boost::mutex::scoped_lock fdmlock(face_done_mutex_);
00217 num_threads_to_wait_for_--;
00218 fdmlock.unlock();
00219 face_detection_done_cond_.notify_one();
00220 }
00221 }
00222
00223 };