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 FACE_DETECTOR_FACES_H
42 #define FACE_DETECTOR_FACES_H
43 
44 #include <string>
45 #include <vector>
46 
47 #include <opencv/cv.hpp>
48 #include <opencv/cxcore.hpp>
49 #include <opencv/cvaux.hpp>
50 
52 #include <boost/thread/mutex.hpp>
53 #include <boost/bind.hpp>
54 #include <boost/thread/thread.hpp>
55 #include <boost/thread/condition.hpp>
56 
57 #define FACE_SIZE_MIN_M 0.1
58 #define FACE_SIZE_MAX_M 0.5
59 #define MAX_FACE_Z_M 8.0
60 // Default thresholds for face tracking.
61 #define FACE_SEP_DIST_M 1.0
63 namespace people
64 {
65 
69 struct Box2D3D
70 {
71  cv::Point2d center2d;
72  cv::Point3d center3d;
73  double width2d;
74  double width3d;
75  cv::Rect box2d;
76  std::string status;
77  int id;
78 };
79 
83 struct Face
84 {
85  std::string id;
86  std::string name;
87 };
88 
93 class Faces
94 {
95 public:
96  // Default thresholds for the face detection algorithm.
97 
98  // Thresholds for the face detection algorithm.
101  double max_face_z_m_;
102  // Thresholds for face tracking.
105  // Create an empty list of people.
106  Faces();
107 
108  // Destroy a list of people.
109  ~Faces();
110 
123  std::vector<Box2D3D> detectAllFacesDisparity(const cv::Mat &image, double threshold, const cv::Mat &disparity_image,
125 
138  std::vector<Box2D3D> detectAllFacesDepth(const cv::Mat &image, double threshold, const cv::Mat &depth_image,
140 
149  void initFaceDetectionDisparity(uint num_cascades, std::string haar_classifier_filename, double face_size_min_m,
150  double face_size_max_m, double max_face_z_m, double face_sep_dist_m);
151 
160  void initFaceDetectionDepth(uint num_cascades, std::string haar_classifier_filename, double face_size_min_m,
161  double face_size_max_m, double max_face_z_m, double face_sep_dist_m);
162 
164 private:
165  std::vector<Face> list_;
166  std::vector<Box2D3D> faces_;
168  cv::Mat cv_image_gray_;
169  cv::Mat const* disparity_image_;
170  cv::Mat const* depth_image_;
173  boost::mutex face_mutex_, face_done_mutex_, t_mutex_;
174  boost::mutex* face_go_mutex_;
175  boost::thread_group threads_;
176  boost::condition face_detection_ready_cond_, face_detection_done_cond_;
179 
180  /* Structures for the face detector. */
181  cv::CascadeClassifier cascade_;
183  void faceDetectionThreadDisparity(uint i);
184  void faceDetectionThreadDepth(uint i);
185 };
186 } // namespace people
187 
188 #endif // FACE_DETECTOR_FACES_H
std::vector< Face > list_
Definition: faces.h:165
boost::condition face_detection_ready_cond_
Definition: faces.h:176
A structure for holding information about boxes in 2d and 3d.
Definition: faces.h:69
int num_threads_to_wait_for_
Definition: faces.h:177
std::string status
Definition: faces.h:76
std::vector< Box2D3D > faces_
Definition: faces.h:166
double width3d
Definition: faces.h:74
cv::Mat const * disparity_image_
Definition: faces.h:169
cv::Mat const * depth_image_
Definition: faces.h:170
cv::Point3d center3d
Definition: faces.h:72
image_geometry::StereoCameraModel * cam_model_
Definition: faces.h:171
double face_size_min_m_
Definition: faces.h:99
double width2d
Definition: faces.h:73
boost::thread_group threads_
Definition: faces.h:175
double face_size_max_m_
Definition: faces.h:100
double max_face_z_m_
Definition: faces.h:101
cv::Rect box2d
Definition: faces.h:75
double face_sep_dist_m_
Definition: faces.h:103
cv::Mat cv_image_gray_
Definition: faces.h:168
boost::mutex t_mutex_
Definition: faces.h:173
int images_ready_
Definition: faces.h:178
cv::Point2d center2d
Definition: faces.h:71
boost::mutex * face_go_mutex_
Definition: faces.h:174
A structure containing the person&#39;s identifying data.
Definition: faces.h:83
std::string name
Definition: faces.h:86
Contains a list of faces and functions that can be performed on that list. This includes utility task...
Definition: faces.h:93
std::string id
Definition: faces.h:85
cv::CascadeClassifier cascade_
Definition: faces.h:181


face_detector
Author(s): Caroline Pantofaru
autogenerated on Sun Feb 21 2021 03:56:45