faces.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Faces-specific computer vision algorithms.
3  *
4  **********************************************************************
5  *
6  * Software License Agreement (BSD License)
7  *
8  * Copyright (c) 2008, Willow Garage, Inc.
9  * All rights reserved.
10  *
11  * Redistribution and use in source and binary forms, with or without
12  * modification, are permitted provided that the following conditions
13  * are met:
14  *
15  * * Redistributions of source code must retain the above copyright
16  * notice, this list of conditions and the following disclaimer.
17  * * Redistributions in binary form must reproduce the above
18  * copyright notice, this list of conditions and the following
19  * disclaimer in the documentation and/or other materials provided
20  * with the distribution.
21  * * Neither the name of the Willow Garage nor the names of its
22  * contributors may be used to endorse or promote products derived
23  * from this software without specific prior written permission.
24  *
25  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
26  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
27  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
28  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
29  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
30  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
31  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
32  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
33  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
34  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
35  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
36  * POSSIBILITY OF SUCH DAMAGE.
37  *********************************************************************/
38 
39 /* Author: Caroline Pantofaru */
40 
41 #include "face_detector/faces.h"
42 #include <cfloat>
43 #include <algorithm>
44 
45 namespace people
46 {
47 
49  list_(NULL),
50  cam_model_(NULL)
51 {
52 }
53 
55 {
56  // Kill all the threads.
57  threads_.interrupt_all();
58  threads_.join_all();
59  delete face_go_mutex_;
60  face_go_mutex_ = NULL;
61 
62  for (int i = list_.size(); i > 0; i--)
63  {
64  list_.pop_back();
65  }
66 
67  cam_model_ = 0;
68 
69 }
70 
71 
72 /* Note: The multi-threading in this file is left over from a previous incarnation that allowed multiple
73  * cascades to be run at once. It hasn't been removed in case we want to return to that model, and since
74  * there isn't much overhead. Right now, however, only one classifier is being run per instantiation
75  * of the face_detector node.
76  */
77 
78 
79 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)
80 {
81  images_ready_ = 0;
82 
83  face_size_min_m_ = face_size_min_m;
84  face_size_max_m_ = face_size_max_m;
85  max_face_z_m_ = max_face_z_m;
86  face_sep_dist_m_ = face_sep_dist_m;
87 
88  face_go_mutex_ = new boost::mutex();
89  bool cascade_ok = cascade_.load(haar_classifier_filename);
90 
91  if (!cascade_ok)
92  {
93  ROS_ERROR_STREAM("Cascade file " << haar_classifier_filename << " doesn't exist.");
94  return;
95  }
96  threads_.create_thread(boost::bind(&Faces::faceDetectionThreadDisparity, this, 0));
97 }
98 
100 
101 vector<Box2D3D> Faces::detectAllFacesDisparity(const cv::Mat &image, double threshold, const cv::Mat &disparity_image, image_geometry::StereoCameraModel *cam_model)
102 {
103 
104  faces_.clear();
105 
106  // Convert the image to grayscale, if necessary.
107 
108  if (image.channels() == 1)
109  {
110  cv_image_gray_.create(image.size(), CV_8UC1);
111  image.copyTo(cv_image_gray_);
112  }
113  else if (image.channels() == 3)
114  {
115  cv_image_gray_.create(image.size(), CV_8UC1);
116  cv::cvtColor(image, cv_image_gray_, CV_BGR2GRAY);
117  }
118  else
119  {
120  std::cerr << "Unknown image type" << std::endl;
121  return faces_;
122  }
123 
124  disparity_image_ = &disparity_image;
125  cam_model_ = cam_model;
126 
127  // Tell the face detection threads that they can run once.
129  boost::mutex::scoped_lock fgmlock(*(face_go_mutex_));
130  images_ready_++;
131  fgmlock.unlock();
132 
133  face_detection_ready_cond_.notify_all();
134 
135  boost::mutex::scoped_lock fdmlock(face_done_mutex_);
136  while (num_threads_to_wait_for_ > 0)
137  {
138  face_detection_done_cond_.wait(fdmlock);
139  }
140 
141  return faces_;
142 }
143 
145 
147 {
148 
149  while (1)
150  {
151  boost::mutex::scoped_lock fgmlock(*(face_go_mutex_));
152  boost::mutex::scoped_lock tlock(t_mutex_, boost::defer_lock);
153  while (1)
154  {
155  tlock.lock();
156  if (images_ready_)
157  {
158  --images_ready_;
159  tlock.unlock();
160  break;
161  }
162  tlock.unlock();
163  face_detection_ready_cond_.wait(fgmlock);
164  }
165 
166  // Find the faces using OpenCV's haar cascade object detector.
167  cv::Point3d p3_1(0, 0, max_face_z_m_);
168  cv::Point3d p3_2(face_size_min_m_, 0, max_face_z_m_);
169  cv::Point2d p2_1 = (cam_model_->left()).project3dToPixel(p3_1);
170  cv::Point2d p2_2 = (cam_model_->left()).project3dToPixel(p3_2);
171  int this_min_face_size = (int)(floor(fabs(p2_2.x - p2_1.x)));
172 
173  std::vector<cv::Rect> faces_vec;
174  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));
175 
176  // Filter the faces using depth information, if available. Currently checks that the actual face size is within the given limits.
177  cv::Scalar color(0, 255, 0);
178  Box2D3D one_face;
179  double avg_disp = 0.0;
180  cv::Mat uvd(1, 3, CV_32FC1);
181  cv::Mat xyz(1, 3, CV_32FC1);
182  // For each face...
183  for (uint iface = 0; iface < faces_vec.size(); iface++) //face_seq->total; iface++) {
184  {
185 
186  one_face.status = "good";
187 
188  one_face.box2d = faces_vec[iface];
189  one_face.id = i; // The cascade that computed this face.
190 
191  // Get the median disparity in the middle half of the bounding box.
192  cv::Mat disp_roi_shallow(*disparity_image_, cv::Rect(floor(one_face.box2d.x + 0.25 * one_face.box2d.width),
193  floor(one_face.box2d.y + 0.25 * one_face.box2d.height),
194  floor(one_face.box2d.x + 0.75 * one_face.box2d.width) - floor(one_face.box2d.x + 0.25 * one_face.box2d.width) + 1,
195  floor(one_face.box2d.y + 0.75 * one_face.box2d.height) - floor(one_face.box2d.y + 0.25 * one_face.box2d.height) + 1));
196  cv::Mat disp_roi = disp_roi_shallow.clone();
197  cv::Mat tmat = disp_roi.reshape(1, disp_roi.rows * disp_roi.cols);
198  cv::Mat tmat_sorted;
199  cv::sort(tmat, tmat_sorted, CV_SORT_EVERY_COLUMN + CV_SORT_DESCENDING);
200  avg_disp = tmat_sorted.at<float>(floor(cv::countNonZero(tmat_sorted >= 0.0) / 2.0)); // Get the middle valid disparity (-1 disparities are invalid)
201 
202  // Fill in the rest of the face data structure.
203  one_face.center2d = cv::Point2d(one_face.box2d.x + one_face.box2d.width / 2.0,
204  one_face.box2d.y + one_face.box2d.height / 2.0);
205  one_face.width2d = one_face.box2d.width;
206 
207  // If the median disparity was valid and the face is a reasonable size, the face status is "good".
208  // If the median disparity was valid but the face isn't a reasonable size, the face status is "bad".
209  // Otherwise, the face status is "unknown".
210  if (avg_disp > 0)
211  {
212  cam_model_->projectDisparityTo3d(cv::Point2d(0.0, 0.0), avg_disp, p3_1);
213  cam_model_->projectDisparityTo3d(cv::Point2d(one_face.box2d.width, 0.0), avg_disp, p3_2);
214  one_face.width3d = fabs(p3_2.x - p3_1.x);
215  cam_model_->projectDisparityTo3d(one_face.center2d, avg_disp, one_face.center3d);
216  if (one_face.center3d.z > max_face_z_m_ || one_face.width3d < face_size_min_m_ || one_face.width3d > face_size_max_m_)
217  {
218  one_face.status = "bad";
219  }
220  }
221  else
222  {
223  one_face.width3d = 0.0;
224  one_face.center3d = cv::Point3d(0.0, 0.0, 0.0);
225  one_face.status = "unknown";
226  }
227 
228  // Add faces to the output vector.
229  // lock faces
230  boost::mutex::scoped_lock lock(face_mutex_);
231  faces_.push_back(one_face);
232  lock.unlock();
233  }
234 
235  boost::mutex::scoped_lock fdmlock(face_done_mutex_);
237  fdmlock.unlock();
238  face_detection_done_cond_.notify_one();
239  }
240 }
241 
243 
244 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)
245 {
246 
247  images_ready_ = 0;
248 
249  face_size_min_m_ = face_size_min_m;
250  face_size_max_m_ = face_size_max_m;
251  max_face_z_m_ = max_face_z_m;
252  face_sep_dist_m_ = face_sep_dist_m;
253 
254  face_go_mutex_ = new boost::mutex();
255  bool cascade_ok = cascade_.load(haar_classifier_filename);
256 
257  if (!cascade_ok)
258  {
259  ROS_ERROR_STREAM("Cascade file " << haar_classifier_filename << " doesn't exist.");
260  return;
261  }
262  threads_.create_thread(boost::bind(&Faces::faceDetectionThreadDepth, this, 0));
263 }
264 
265 
267 
268 vector<Box2D3D> Faces::detectAllFacesDepth(const cv::Mat &image, double threshold, const cv::Mat &dimage, image_geometry::StereoCameraModel *cam_model)
269 {
270 
271  faces_.clear();
272 
273  // Convert the image to grayscale, if necessary.
274 
275  if (image.channels() == 1)
276  {
277  cv_image_gray_.create(image.size(), CV_8UC1);
278  image.copyTo(cv_image_gray_);
279  }
280  else if (image.channels() == 3)
281  {
282  cv_image_gray_.create(image.size(), CV_8UC1);
283  cv::cvtColor(image, cv_image_gray_, CV_BGR2GRAY);
284  }
285  else
286  {
287  std::cerr << "Unknown image type" << std::endl;
288  return faces_;
289  }
290 
291  depth_image_ = &dimage;
292  cam_model_ = cam_model;
293 
294  // Tell the face detection threads that they can run once.
296  boost::mutex::scoped_lock fgmlock(*(face_go_mutex_));
297  images_ready_++;
298  fgmlock.unlock();
299 
300  face_detection_ready_cond_.notify_all();
301 
302  boost::mutex::scoped_lock fdmlock(face_done_mutex_);
303  while (num_threads_to_wait_for_ > 0)
304  {
305  face_detection_done_cond_.wait(fdmlock);
306  }
307 
308  return faces_;
309 }
310 
312 
314 {
315 
316  while (1)
317  {
318  boost::mutex::scoped_lock fgmlock(*(face_go_mutex_));
319  boost::mutex::scoped_lock tlock(t_mutex_, boost::defer_lock);
320  while (1)
321  {
322  tlock.lock();
323  if (images_ready_)
324  {
325  --images_ready_;
326  tlock.unlock();
327  break;
328  }
329  tlock.unlock();
330  face_detection_ready_cond_.wait(fgmlock);
331  }
332 
333  // Find the faces using OpenCV's haar cascade object detector.
334  cv::Point3d p3_1(0, 0, max_face_z_m_);
335  cv::Point3d p3_2(face_size_min_m_, 0, max_face_z_m_);
336  cv::Point2d p2_1 = (cam_model_->left()).project3dToPixel(p3_1);
337  cv::Point2d p2_2 = (cam_model_->left()).project3dToPixel(p3_2);
338  int this_min_face_size = (int)(floor(fabs(p2_2.x - p2_1.x)));
339 
340  std::vector<cv::Rect> faces_vec;
341  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));
342 
343  // Filter the faces using depth information, if available. Currently checks that the actual face size is within the given limits.
344  cv::Scalar color(0, 255, 0);
345  Box2D3D one_face;
346  double avg_d = 0.0;
347  cv::Mat uvd(1, 3, CV_32FC1);
348  cv::Mat xyz(1, 3, CV_32FC1);
349  // For each face...
350  for (uint iface = 0; iface < faces_vec.size(); iface++)
351  {
352 
353  one_face.status = "good";
354 
355  one_face.box2d = faces_vec[iface];
356  one_face.id = i; // The cascade that computed this face.
357 
358  // Get the median depth in the middle half of the bounding box.
359  cv::Mat depth_roi_shallow(*depth_image_, cv::Rect(floor(one_face.box2d.x + 0.25 * one_face.box2d.width),
360  floor(one_face.box2d.y + 0.25 * one_face.box2d.height),
361  floor(one_face.box2d.x + 0.75 * one_face.box2d.width) - floor(one_face.box2d.x + 0.25 * one_face.box2d.width) + 1,
362  floor(one_face.box2d.y + 0.75 * one_face.box2d.height) - floor(one_face.box2d.y + 0.25 * one_face.box2d.height) + 1));
363 
364  // Fill in the rest of the face data structure.
365  one_face.center2d = cv::Point2d(one_face.box2d.x + one_face.box2d.width / 2.0,
366  one_face.box2d.y + one_face.box2d.height / 2.0);
367  one_face.width2d = one_face.box2d.width;
368 
369 
370  // If the median depth was valid and the face is a reasonable size, the face status is "good".
371  // If the median depth was valid but the face isn't a reasonable size, the face status is "bad".
372  // Otherwise, the face status is "unknown".
373 
374  std::vector<float> depths;
375  // Copy the depths removing the nans.
376  for (int i = 0; i < depth_roi_shallow.rows; i++)
377  {
378  const float* dptr = depth_roi_shallow.ptr<float>(i);
379  for (int j = 0; j < depth_roi_shallow.cols; j++)
380  {
381  if (dptr[j] == dptr[j])
382  {
383  depths.push_back(dptr[j]);
384  }
385  }
386  }
387 
388  std::vector<float>::iterator dbegin = depths.begin();
389  std::vector<float>::iterator dend = depths.end();
390 
391  if (depths.size() > 0)
392  {
393  std::sort(dbegin, dend);
394  avg_d = depths[floor(depths.size() / 2.0)];
395 
396  one_face.width3d = fabs((cam_model_->left()).getDeltaX(one_face.box2d.width, avg_d));
397  one_face.center3d = (cam_model_->left()).projectPixelTo3dRay(one_face.center2d);
398 
399  one_face.center3d = (avg_d / one_face.center3d.z) * one_face.center3d;
400  if (one_face.center3d.z > max_face_z_m_ || one_face.width3d < face_size_min_m_ || one_face.width3d > face_size_max_m_)
401  {
402  one_face.status = "bad";
403  }
404  }
405  else
406  {
407  one_face.width3d = 0.0;
408  one_face.center3d = cv::Point3d(0.0, 0.0, 0.0);
409  one_face.status = "unknown";
410  }
411 
412  // Add faces to the output vector.
413  // lock faces
414  boost::mutex::scoped_lock lock(face_mutex_);
415  faces_.push_back(one_face);
416  lock.unlock();
417  }
418 
419  boost::mutex::scoped_lock fdmlock(face_done_mutex_);
421  fdmlock.unlock();
422  face_detection_done_cond_.notify_one();
423  }
424 
425 }
426 
427 };
boost::condition face_detection_ready_cond_
Definition: faces.h:190
A structure for holding information about boxes in 2d and 3d.
Definition: faces.h:78
int num_threads_to_wait_for_
Definition: faces.h:191
vector< Face > list_
Definition: faces.h:179
const PinholeCameraModel & left() const
double width3d
Definition: faces.h:83
string status
Definition: faces.h:85
cv::Mat const * disparity_image_
Definition: faces.h:183
cv::Mat const * depth_image_
Definition: faces.h:184
Definition: faces.h:71
cv::Point3d center3d
Definition: faces.h:81
image_geometry::StereoCameraModel * cam_model_
Definition: faces.h:185
double face_size_min_m_
Definition: faces.h:112
void projectDisparityTo3d(const cv::Point2d &left_uv_rect, float disparity, cv::Point3d &xyz) const
double width2d
Definition: faces.h:82
boost::thread_group threads_
Definition: faces.h:189
double face_size_max_m_
Definition: faces.h:113
void faceDetectionThreadDepth(uint i)
Definition: faces.cpp:313
double max_face_z_m_
Definition: faces.h:114
cv::Rect box2d
Definition: faces.h:84
boost::condition face_detection_done_cond_
Definition: faces.h:190
double face_sep_dist_m_
Definition: faces.h:116
cv::Mat cv_image_gray_
Definition: faces.h:182
boost::mutex t_mutex_
Definition: faces.h:187
void faceDetectionThreadDisparity(uint i)
Definition: faces.cpp:146
int images_ready_
Definition: faces.h:192
cv::Point2d center2d
Definition: faces.h:80
boost::mutex * face_go_mutex_
Definition: faces.h:188
vector< Box2D3D > faces_
Definition: faces.h:180
boost::mutex face_mutex_
Definition: faces.h:187
vector< Box2D3D > detectAllFacesDisparity(const cv::Mat &image, double threshold, const cv::Mat &disparity_image, image_geometry::StereoCameraModel *cam_model)
Detect all faces in an image and disparity image.
Definition: faces.cpp:101
void 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)
Initialize the face detector with images and depth.
Definition: faces.cpp:244
vector< Box2D3D > detectAllFacesDepth(const cv::Mat &image, double threshold, const cv::Mat &depth_image, image_geometry::StereoCameraModel *cam_model)
Detect all faces in an image and depth image.
Definition: faces.cpp:268
boost::mutex face_done_mutex_
Definition: faces.h:187
void 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)
Initialize the face detector with images and disparities.
Definition: faces.cpp:79
#define ROS_ERROR_STREAM(args)
cv::CascadeClassifier cascade_
Definition: faces.h:195


face_detector
Author(s): Caroline Pantofaru
autogenerated on Fri Jun 7 2019 22:07:47