62 for (
int i =
list_.size(); i > 0; i--)
79 void Faces::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)
89 bool cascade_ok =
cascade_.load(haar_classifier_filename);
93 ROS_ERROR_STREAM(
"Cascade file " << haar_classifier_filename <<
" doesn't exist.");
108 if (image.channels() == 1)
113 else if (image.channels() == 3)
120 std::cerr <<
"Unknown image type" << std::endl;
152 boost::mutex::scoped_lock tlock(
t_mutex_, boost::defer_lock);
171 int this_min_face_size = (int)(floor(fabs(p2_2.x - p2_1.x)));
173 std::vector<cv::Rect> faces_vec;
174 cascade_.detectMultiScale(
cv_image_gray_, faces_vec, 1.2, 2, CV_HAAR_DO_CANNY_PRUNING, cv::Size(this_min_face_size, this_min_face_size));
177 cv::Scalar color(0, 255, 0);
179 double avg_disp = 0.0;
180 cv::Mat uvd(1, 3, CV_32FC1);
181 cv::Mat xyz(1, 3, CV_32FC1);
183 for (uint iface = 0; iface < faces_vec.size(); iface++)
188 one_face.
box2d = faces_vec[iface];
193 floor(one_face.
box2d.y + 0.25 * one_face.
box2d.height),
194 floor(one_face.
box2d.x + 0.75 * one_face.
box2d.width) - floor(one_face.
box2d.x + 0.25 * one_face.
box2d.width) + 1,
195 floor(one_face.
box2d.y + 0.75 * one_face.
box2d.height) - floor(one_face.
box2d.y + 0.25 * one_face.
box2d.height) + 1));
196 cv::Mat disp_roi = disp_roi_shallow.clone();
197 cv::Mat tmat = disp_roi.reshape(1, disp_roi.rows * disp_roi.cols);
199 cv::sort(tmat, tmat_sorted, CV_SORT_EVERY_COLUMN + CV_SORT_DESCENDING);
200 avg_disp = tmat_sorted.at<
float>(floor(cv::countNonZero(tmat_sorted >= 0.0) / 2.0));
204 one_face.
box2d.y + one_face.
box2d.height / 2.0);
214 one_face.
width3d = fabs(p3_2.x - p3_1.x);
224 one_face.
center3d = cv::Point3d(0.0, 0.0, 0.0);
225 one_face.
status =
"unknown";
231 faces_.push_back(one_face);
244 void Faces::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)
255 bool cascade_ok =
cascade_.load(haar_classifier_filename);
259 ROS_ERROR_STREAM(
"Cascade file " << haar_classifier_filename <<
" doesn't exist.");
275 if (image.channels() == 1)
280 else if (image.channels() == 3)
287 std::cerr <<
"Unknown image type" << std::endl;
319 boost::mutex::scoped_lock tlock(
t_mutex_, boost::defer_lock);
338 int this_min_face_size = (int)(floor(fabs(p2_2.x - p2_1.x)));
340 std::vector<cv::Rect> faces_vec;
341 cascade_.detectMultiScale(
cv_image_gray_, faces_vec, 1.2, 2, CV_HAAR_DO_CANNY_PRUNING, cv::Size(this_min_face_size, this_min_face_size));
344 cv::Scalar color(0, 255, 0);
347 cv::Mat uvd(1, 3, CV_32FC1);
348 cv::Mat xyz(1, 3, CV_32FC1);
350 for (uint iface = 0; iface < faces_vec.size(); iface++)
355 one_face.
box2d = faces_vec[iface];
360 floor(one_face.
box2d.y + 0.25 * one_face.
box2d.height),
361 floor(one_face.
box2d.x + 0.75 * one_face.
box2d.width) - floor(one_face.
box2d.x + 0.25 * one_face.
box2d.width) + 1,
362 floor(one_face.
box2d.y + 0.75 * one_face.
box2d.height) - floor(one_face.
box2d.y + 0.25 * one_face.
box2d.height) + 1));
366 one_face.
box2d.y + one_face.
box2d.height / 2.0);
374 std::vector<float> depths;
376 for (
int i = 0; i < depth_roi_shallow.rows; i++)
378 const float* dptr = depth_roi_shallow.ptr<
float>(i);
379 for (
int j = 0; j < depth_roi_shallow.cols; j++)
381 if (dptr[j] == dptr[j])
383 depths.push_back(dptr[j]);
388 std::vector<float>::iterator dbegin = depths.begin();
389 std::vector<float>::iterator dend = depths.end();
391 if (depths.size() > 0)
393 std::sort(dbegin, dend);
394 avg_d = depths[floor(depths.size() / 2.0)];
408 one_face.
center3d = cv::Point3d(0.0, 0.0, 0.0);
409 one_face.
status =
"unknown";
415 faces_.push_back(one_face);
boost::condition face_detection_ready_cond_
A structure for holding information about boxes in 2d and 3d.
int num_threads_to_wait_for_
const PinholeCameraModel & left() const
cv::Mat const * disparity_image_
cv::Mat const * depth_image_
image_geometry::StereoCameraModel * cam_model_
void projectDisparityTo3d(const cv::Point2d &left_uv_rect, float disparity, cv::Point3d &xyz) const
boost::thread_group threads_
void faceDetectionThreadDepth(uint i)
boost::condition face_detection_done_cond_
void faceDetectionThreadDisparity(uint i)
boost::mutex * face_go_mutex_
vector< Box2D3D > detectAllFacesDisparity(const cv::Mat &image, double threshold, const cv::Mat &disparity_image, image_geometry::StereoCameraModel *cam_model)
Detect all faces in an image and disparity image.
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)
Initialize the face detector with images and depth.
vector< Box2D3D > detectAllFacesDepth(const cv::Mat &image, double threshold, const cv::Mat &depth_image, image_geometry::StereoCameraModel *cam_model)
Detect all faces in an image and depth image.
boost::mutex face_done_mutex_
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)
Initialize the face detector with images and disparities.
#define ROS_ERROR_STREAM(args)
cv::CascadeClassifier cascade_