faces.h
Go to the documentation of this file.
1 /*********************************************************************
2 * Face-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 #ifndef FACES_H
42 #define FACES_H
43 
44 
45 
46 #include <stdio.h>
47 #include <iostream>
48 #include <vector>
49 
50 #include <opencv/cv.hpp>
51 #include <opencv/cxcore.hpp>
52 #include <opencv/cvaux.hpp>
53 
55 #include "ros/time.h"
56 #include <ros/console.h>
57 #include <boost/thread/mutex.hpp>
58 #include <boost/bind.hpp>
59 #include <boost/thread/thread.hpp>
60 #include <boost/thread/condition.hpp>
61 
62 
63 using namespace std;
64 
65 #define FACE_SIZE_MIN_M 0.1
66 #define FACE_SIZE_MAX_M 0.5
67 #define MAX_FACE_Z_M 8.0
68 // Default thresholds for face tracking.
69 #define FACE_SEP_DIST_M 1.0
71 namespace people
72 {
73 
74 
78 struct Box2D3D
79 {
80  cv::Point2d center2d;
81  cv::Point3d center3d;
82  double width2d;
83  double width3d;
84  cv::Rect box2d;
85  string status;
86  int id;
87 };
88 
89 
93 struct Face
94 {
95  string id;
96  string name;
97 };
98 
99 
105 class Faces
106 {
107 public:
108 
109  // Default thresholds for the face detection algorithm.
110 
111  // Thresholds for the face detection algorithm.
114  double max_face_z_m_;
115  // Thresholds for face tracking.
120  // Create an empty list of people.
121  Faces();
122 
123  // Destroy a list of people.
124  ~Faces();
125 
126 
139  vector<Box2D3D> detectAllFacesDisparity(const cv::Mat &image, double threshold, const cv::Mat &disparity_image, image_geometry::StereoCameraModel *cam_model);
140 
153  vector<Box2D3D> detectAllFacesDepth(const cv::Mat &image, double threshold, const cv::Mat &depth_image, image_geometry::StereoCameraModel *cam_model);
154 
163  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);
164 
165 
174  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);
175 
177 private:
178 
179  vector<Face> list_;
180  vector<Box2D3D> faces_;
182  cv::Mat cv_image_gray_;
183  cv::Mat const* disparity_image_;
184  cv::Mat const* depth_image_;
187  boost::mutex face_mutex_, face_done_mutex_, t_mutex_;
188  boost::mutex* face_go_mutex_;
189  boost::thread_group threads_;
190  boost::condition face_detection_ready_cond_, face_detection_done_cond_;
193 
194  /* Structures for the face detector. */
195  cv::CascadeClassifier cascade_;
197  void faceDetectionThreadDisparity(uint i);
198  void faceDetectionThreadDepth(uint i);
199 
200 };
201 
202 };
203 
204 #endif
205 
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
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
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
double width2d
Definition: faces.h:82
boost::thread_group threads_
Definition: faces.h:189
double face_size_max_m_
Definition: faces.h:113
double max_face_z_m_
Definition: faces.h:114
cv::Rect box2d
Definition: faces.h:84
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
string name
Definition: faces.h:96
int images_ready_
Definition: faces.h:192
cv::Point2d center2d
Definition: faces.h:80
boost::mutex * face_go_mutex_
Definition: faces.h:188
A structure containing the person&#39;s identifying data.
Definition: faces.h:93
vector< Box2D3D > faces_
Definition: faces.h:180
Contains a list of faces and functions that can be performed on that list. This includes utility task...
Definition: faces.h:105
string id
Definition: faces.h:95
cv::CascadeClassifier cascade_
Definition: faces.h:195


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