00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042 #ifndef FACES_H
00043 #define FACES_H
00044
00045
00046
00047 #include <stdio.h>
00048 #include <stdlib.h>
00049 #include <iostream>
00050 #include <vector>
00051
00052 #include <opencv/cv.hpp>
00053 #include <opencv/cxcore.hpp>
00054 #include <opencv/cvaux.hpp>
00055
00056 #include "image_geometry/stereo_camera_model.h"
00057 #include "ros/time.h"
00058 #include <boost/thread/mutex.hpp>
00059 #include <boost/bind.hpp>
00060 #include <boost/thread/thread.hpp>
00061 #include <boost/thread/condition.hpp>
00062
00063 #include <pcl/point_types.h>
00064 #include <pcl_ros/point_cloud.h>
00065
00066 using namespace std;
00067
00068
00069 namespace people {
00070
00071
00075 struct Box2D3D {
00076 cv::Point2d center2d;
00077 cv::Point3d center3d;
00078 double radius2d;
00079 double radius3d;
00080 cv::Rect box2d;
00081 string status;
00082 int id;
00083 };
00084
00085
00089 struct Face {
00090 string id;
00091 string name;
00092 };
00093
00094
00099 class Faces
00100 {
00101 public:
00102
00103
00104 static const double FACE_SIZE_MIN_M=0.1;
00105 static const double FACE_SIZE_MAX_M=0.5;
00106 static const double MAX_FACE_Z_M=8.0;
00107
00108 static const double FACE_SEP_DIST_M=1.0;
00110
00111 double face_size_min_m_;
00112 double face_size_max_m_;
00113 double max_face_z_m_;
00114
00115 double face_sep_dist_m_;
00119
00120 Faces();
00121
00122
00123 ~Faces();
00124
00125
00138 vector<Box2D3D> detectAllFaces(cv::Mat &image, double threshold, cv::Mat &disparity_image, image_geometry::StereoCameraModel *cam_model, pcl::PointCloud<pcl::PointXYZ>* depth_cloud = 0);
00139
00148 void initFaceDetection(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);
00149
00151 private:
00152
00153 vector<Face> list_;
00154 vector<Box2D3D> faces_;
00156 cv::Mat cv_image_gray_;
00157 cv::Mat *disparity_image_;
00158 pcl::PointCloud<pcl::PointXYZ>* depth_cloud_;
00159 image_geometry::StereoCameraModel *cam_model_;
00161 boost::mutex face_mutex_, face_done_mutex_, t_mutex_;
00162 boost::mutex* face_go_mutex_;
00163 boost::thread_group threads_;
00164 boost::condition face_detection_ready_cond_, face_detection_done_cond_;
00165 int num_threads_to_wait_for_;
00166 int images_ready_;
00167
00168
00169 cv::CascadeClassifier cascade_;
00171 void faceDetectionThread(uint i);
00172
00173 };
00174
00175 };
00176
00177 #endif
00178