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>
Public Member Functions | |
| 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. More... | |
| 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. More... | |
| 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. More... | |
| 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. More... | |
| ~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::StereoCameraModel * | cam_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< Box2D3D > | faces_ |
| int | images_ready_ |
| vector< Face > | list_ |
| int | num_threads_to_wait_for_ |
| boost::mutex | t_mutex_ |
| boost::thread_group | threads_ |
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.
| 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:
| 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. |
| depth_image | Image of depth (e.g. from an RGBD camera). |
| 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. |
| 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:
| 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. |
|
private |
|
private |
| 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:
| num_cascades | Should always be 1 (may change in the future.) |
| haar_classifier_filename | Full path to the cascade file. |
| 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:
| num_cascades | Should always be 1 (may change in the future.) |
| haar_classifier_filename | Full path to the cascade file. |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
| double people::Faces::face_sep_dist_m_ |
| double people::Faces::face_size_max_m_ |
| double people::Faces::face_size_min_m_ |
|
private |
|
private |
| double people::Faces::max_face_z_m_ |