41 #ifndef FACE_DETECTOR_FACES_H 42 #define FACE_DETECTOR_FACES_H 47 #include <opencv/cv.hpp> 48 #include <opencv/cxcore.hpp> 49 #include <opencv/cvaux.hpp> 52 #include <boost/thread/mutex.hpp> 53 #include <boost/bind.hpp> 54 #include <boost/thread/thread.hpp> 55 #include <boost/thread/condition.hpp> 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 123 std::vector<Box2D3D> detectAllFacesDisparity(
const cv::Mat &image,
double threshold,
const cv::Mat &disparity_image,
138 std::vector<Box2D3D> detectAllFacesDepth(
const cv::Mat &image,
double threshold,
const cv::Mat &depth_image,
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);
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);
173 boost::mutex face_mutex_, face_done_mutex_,
t_mutex_;
183 void faceDetectionThreadDisparity(uint i);
184 void faceDetectionThreadDepth(uint i);
188 #endif // FACE_DETECTOR_FACES_H std::vector< Face > list_
boost::condition face_detection_ready_cond_
A structure for holding information about boxes in 2d and 3d.
int num_threads_to_wait_for_
std::vector< Box2D3D > faces_
cv::Mat const * disparity_image_
cv::Mat const * depth_image_
image_geometry::StereoCameraModel * cam_model_
boost::thread_group threads_
boost::mutex * face_go_mutex_
A structure containing the person's identifying data.
Contains a list of faces and functions that can be performed on that list. This includes utility task...
cv::CascadeClassifier cascade_