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< Box2D3DdetectAllFaces (cv::Mat &image, double threshold, cv::Mat &disparity_image, image_geometry::StereoCameraModel *cam_model)
 Detect all faces in an image.
 Faces ()
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)
 Initialize the face detector.
 ~Faces ()

Public Attributes

double face_sep_dist_m_
double face_size_max_m_
double face_size_min_m_
double max_face_z_m_

Static Public Attributes

static const double FACE_SEP_DIST_M = 1.0
static const double FACE_SIZE_MAX_M = 0.5
static const double FACE_SIZE_MIN_M = 0.1
static const double MAX_FACE_Z_M = 8.0

Private Member Functions

void faceDetectionThread (uint i)

Private Attributes

image_geometry::StereoCameraModel * cam_model_
cv::CascadeClassifier cascade_
cv::Mat cv_image_gray_
cv::Mat * 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 95 of file faces.h.


Constructor & Destructor Documentation

people::Faces::Faces (  ) 

Definition at line 46 of file faces.cpp.

people::Faces::~Faces (  ) 

Definition at line 51 of file faces.cpp.


Member Function Documentation

vector< Box2D3D > people::Faces::detectAllFaces ( cv::Mat &  image,
double  threshold,
cv::Mat &  disparity_image,
image_geometry::StereoCameraModel *  cam_model 
)

Detect all faces in an image.

Input:

Parameters:
image The image in which to detect faces.
haar_classifier_filename Path to the xml file containing the trained haar classifier cascade.
threshold Detection threshold. Currently unused.
disparity_image Image of disparities (from stereo).
cam_model The 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 94 of file faces.cpp.

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

Definition at line 134 of file faces.cpp.

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

Initialize the face detector.

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

Parameters:
num_cascades Should always be 1 (may change in the future.)
haar_classifier_filename Full path to the cascade file.

Definition at line 74 of file faces.cpp.


Member Data Documentation

image_geometry::StereoCameraModel* people::Faces::cam_model_ [private]

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

Definition at line 154 of file faces.h.

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

Classifier cascade for face detection.

Definition at line 164 of file faces.h.

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

Grayscale image

Definition at line 152 of file faces.h.

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

Disparity image

Definition at line 153 of file faces.h.

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

Definition at line 159 of file faces.h.

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

Definition at line 159 of file faces.h.

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

Definition at line 156 of file faces.h.

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

Definition at line 157 of file faces.h.

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

Definition at line 156 of file faces.h.

const double people::Faces::FACE_SEP_DIST_M = 1.0 [static]

Default separation distance for associating faces. Only use this for initialization.

Definition at line 104 of file faces.h.

Separation distance for associating faces.

Definition at line 111 of file faces.h.

const double people::Faces::FACE_SIZE_MAX_M = 0.5 [static]

Default maximum face size, in meters. Only use this for initialization.

Definition at line 101 of file faces.h.

Maximum face size, in meters.

Definition at line 108 of file faces.h.

const double people::Faces::FACE_SIZE_MIN_M = 0.1 [static]

Default minimum face size, in meters. Only use this for initialization.

Definition at line 100 of file faces.h.

Minimum face size, in meters.

Definition at line 107 of file faces.h.

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

The list of face positions.

Definition at line 150 of file faces.h.

Definition at line 161 of file faces.h.

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

The list of face ids.

Definition at line 149 of file faces.h.

const double people::Faces::MAX_FACE_Z_M = 8.0 [static]

Default maximum distance from the camera, in meters. Only use this for initialization.

Definition at line 102 of file faces.h.

Maximum distance from the camera, in meters.

Definition at line 109 of file faces.h.

Definition at line 160 of file faces.h.

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

Definition at line 156 of file faces.h.

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

Definition at line 158 of file faces.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs


face_detector
Author(s): Caroline Pantofaru
autogenerated on Fri Jan 11 09:12:42 2013