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


face_detector
Author(s): Caroline Pantofaru
autogenerated on Wed Mar 2 2022 00:45:07