#include <head_detector.h>
Public Member Functions | |
virtual unsigned long | detectRangeFace (cv::Mat &depth_image, std::vector< cv::Rect > &rangeFaceCoordinates, bool fillUnassignedDepthValues=false) |
HeadDetector (void) | |
Constructor. | |
virtual unsigned long | init (std::string model_directory, double depth_increase_search_scale, int depth_drop_groups, int depth_min_search_scale_x, int depth_min_search_scale_y) |
~HeadDetector (void) | |
Destructor. | |
Protected Member Functions | |
unsigned long | interpolateUnassignedPixels (cv::Mat &img) |
Protected Attributes | |
int | m_depth_drop_groups |
Minimum number (minus 1) of neighbor rectangles that makes up an object. | |
double | m_depth_increase_search_scale |
The factor by which the search window is scaled between the subsequent scans. | |
int | m_depth_min_search_scale_x |
Minimum search scale x. | |
int | m_depth_min_search_scale_y |
Minimum search scale y. | |
bool | m_initialized |
indicates whether the class was already initialized | |
CvHaarClassifierCascade * | m_range_cascade |
Haar-Classifier for range-detection. | |
CvMemStorage * | m_storage |
Storage for face and eye detection. |
Definition at line 75 of file head_detector.h.
HeadDetector::HeadDetector | ( | void | ) |
HeadDetector::~HeadDetector | ( | void | ) |
Destructor.
Definition at line 102 of file head_detector.cpp.
unsigned long HeadDetector::detectRangeFace | ( | cv::Mat & | depth_image, |
std::vector< cv::Rect > & | rangeFaceCoordinates, | ||
bool | fillUnassignedDepthValues = false |
||
) | [virtual] |
Function to detect the face on range image The function detects the face in a given range image
img | Depth image of the depth camera (in format CV_32FC3 - one channel for x, y and z) |
rangeFaceCoordinates | Vector with the bounding boxes (image coordinates) of detected heads in range image |
fillUnassignedDepthValues | this parameter should be true if the kinect sensor is used (activates a filling method for black pixels) |
Definition at line 153 of file head_detector.cpp.
unsigned long HeadDetector::init | ( | std::string | model_directory, |
double | depth_increase_search_scale, | ||
int | depth_drop_groups, | ||
int | depth_min_search_scale_x, | ||
int | depth_min_search_scale_y | ||
) | [virtual] |
Initialization function.
model_directory | The directory for data files |
depth_increase_search_scale | The factor by which the search window is scaled between the subsequent scans |
depth_drop_groups | Minimum number (minus 1) of neighbor rectangles that makes up an object. |
depth_min_search_scale_x | Minimum search scale x |
depth_min_search_scale_y | Minimum search scale y |
Definition at line 81 of file head_detector.cpp.
unsigned long HeadDetector::interpolateUnassignedPixels | ( | cv::Mat & | img | ) | [protected] |
interpolates unassigned pixels in the depth image when using the kinect
img | depth image |
Definition at line 109 of file head_detector.cpp.
int ipa_PeopleDetector::HeadDetector::m_depth_drop_groups [protected] |
Minimum number (minus 1) of neighbor rectangles that makes up an object.
Definition at line 107 of file head_detector.h.
double ipa_PeopleDetector::HeadDetector::m_depth_increase_search_scale [protected] |
The factor by which the search window is scaled between the subsequent scans.
Definition at line 106 of file head_detector.h.
int ipa_PeopleDetector::HeadDetector::m_depth_min_search_scale_x [protected] |
Minimum search scale x.
Definition at line 108 of file head_detector.h.
int ipa_PeopleDetector::HeadDetector::m_depth_min_search_scale_y [protected] |
Minimum search scale y.
Definition at line 109 of file head_detector.h.
bool ipa_PeopleDetector::HeadDetector::m_initialized [protected] |
indicates whether the class was already initialized
Definition at line 114 of file head_detector.h.
CvHaarClassifierCascade* ipa_PeopleDetector::HeadDetector::m_range_cascade [protected] |
Haar-Classifier for range-detection.
Definition at line 112 of file head_detector.h.
CvMemStorage* ipa_PeopleDetector::HeadDetector::m_storage [protected] |
Storage for face and eye detection.
Definition at line 111 of file head_detector.h.