Public Member Functions | Public Attributes | Private Member Functions | Private Attributes
people::Faces Class Reference

Contains a list of faces and functions that can be performed on that list. This includes utility tasks such as set/get data, to more complicated tasks such as detection or tracking. More...

#include <faces.h>

List of all members.

Public Member Functions

vector< Box2D3DdetectAllFacesDepth (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.
vector< Box2D3DdetectAllFacesDisparity (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.
 Faces ()
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.
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.
 ~Faces ()

Public Attributes

double face_sep_dist_m_
double face_size_max_m_
double face_size_min_m_
double max_face_z_m_

Private Member Functions

void faceDetectionThreadDepth (uint i)
void faceDetectionThreadDisparity (uint i)

Private Attributes

image_geometry::StereoCameraModelcam_model_
cv::CascadeClassifier cascade_
cv::Mat cv_image_gray_
cv::Mat const * depth_image_
cv::Mat const * disparity_image_
boost::condition face_detection_done_cond_
boost::condition face_detection_ready_cond_
boost::mutex face_done_mutex_
boost::mutex * face_go_mutex_
boost::mutex face_mutex_
vector< Box2D3Dfaces_
int images_ready_
vector< Facelist_
int num_threads_to_wait_for_
boost::mutex t_mutex_
boost::thread_group threads_

Detailed Description

Contains a list of faces and functions that can be performed on that list. This includes utility tasks such as set/get data, to more complicated tasks such as detection or tracking.

Definition at line 105 of file faces.h.


Constructor & Destructor Documentation

Definition at line 48 of file faces.cpp.

Definition at line 54 of file faces.cpp.


Member Function Documentation

vector< Box2D3D > people::Faces::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.

Input:

Parameters:
imageThe image in which to detect faces.
haar_classifier_filenamePath to the xml file containing the trained haar classifier cascade.
thresholdDetection threshold. Currently unused.
depth_imageImage of depth (e.g. from an RGBD camera).
cam_modelThe camera model used to convert 2D points to 3D points. Output: A vector of Box2D3Ds containing the bounding boxes around found faces in 2D and 3D.

Definition at line 268 of file faces.cpp.

vector< Box2D3D > people::Faces::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.

Input:

Parameters:
imageThe image in which to detect faces.
haar_classifier_filenamePath to the xml file containing the trained haar classifier cascade.
thresholdDetection threshold. Currently unused.
disparity_imageImage of disparities (from stereo).
cam_modelThe camera model used to convert 2D points to 3D points. Output: A vector of Box2D3Ds containing the bounding boxes around found faces in 2D and 3D.

Definition at line 101 of file faces.cpp.

void people::Faces::faceDetectionThreadDepth ( uint  i) [private]

Definition at line 313 of file faces.cpp.

void people::Faces::faceDetectionThreadDisparity ( uint  i) [private]

Definition at line 146 of file faces.cpp.

void people::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 
)

Initialize the face detector with images and depth.

Initialize the face detector, including loading in the classifier cascade. Input:

Parameters:
num_cascadesShould always be 1 (may change in the future.)
haar_classifier_filenameFull path to the cascade file.

Definition at line 244 of file faces.cpp.

void people::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 
)

Initialize the face detector with images and disparities.

Initialize the face detector, including loading in the classifier cascade. Input:

Parameters:
num_cascadesShould always be 1 (may change in the future.)
haar_classifier_filenameFull path to the cascade file.

Definition at line 79 of file faces.cpp.


Member Data Documentation

The stereo camera model for 2D-->3D conversions.

Definition at line 185 of file faces.h.

cv::CascadeClassifier people::Faces::cascade_ [private]

Classifier cascade for face detection.

Definition at line 195 of file faces.h.

cv::Mat people::Faces::cv_image_gray_ [private]

Grayscale image

Definition at line 182 of file faces.h.

cv::Mat const* people::Faces::depth_image_ [private]

Depth image

Definition at line 184 of file faces.h.

cv::Mat const* people::Faces::disparity_image_ [private]

Disparity image

Definition at line 183 of file faces.h.

boost::condition people::Faces::face_detection_done_cond_ [private]

Definition at line 190 of file faces.h.

boost::condition people::Faces::face_detection_ready_cond_ [private]

Definition at line 190 of file faces.h.

boost::mutex people::Faces::face_done_mutex_ [private]

Definition at line 187 of file faces.h.

boost::mutex* people::Faces::face_go_mutex_ [private]

Definition at line 188 of file faces.h.

boost::mutex people::Faces::face_mutex_ [private]

Definition at line 187 of file faces.h.

Separation distance for associating faces.

Definition at line 116 of file faces.h.

Maximum face size, in meters.

Definition at line 113 of file faces.h.

Minimum face size, in meters.

Definition at line 112 of file faces.h.

vector<Box2D3D> people::Faces::faces_ [private]

The list of face positions.

Definition at line 180 of file faces.h.

Definition at line 192 of file faces.h.

vector<Face> people::Faces::list_ [private]

The list of face ids.

Definition at line 179 of file faces.h.

Maximum distance from the camera, in meters.

Definition at line 114 of file faces.h.

Definition at line 191 of file faces.h.

boost::mutex people::Faces::t_mutex_ [private]

Definition at line 187 of file faces.h.

boost::thread_group people::Faces::threads_ [private]

Definition at line 189 of file faces.h.


The documentation for this class was generated from the following files:


face_detector
Author(s): Caroline Pantofaru
autogenerated on Sat Jun 8 2019 18:40:20