#include <people_detector.h>
Public Member Functions | |
| virtual unsigned long | AddFace (cv::Mat &img, cv::Rect &face, std::string id, std::vector< cv::Mat > &images, std::vector< std::string > &ids) |
| virtual unsigned long | CalculateFaceClasses (cv::Mat &projectedTrainFaceMat, std::vector< std::string > &id, int *nEigens, cv::Mat &faceClassAvgProjections, std::vector< std::string > &idUnique, cv::ml::SVM *personClassifier=0) |
| virtual unsigned long | ClassifyFace (float *projectedTestFace, int *nearest, int *nEigens, cv::Mat &projectedTrainFaceMat, int *threshold, cv::Mat &eigenValMat, cv::ml::SVM *personClassifier=0) |
| virtual unsigned long | ConvertAndResize (cv::Mat &img, cv::Mat &resized, cv::Rect &face) |
| virtual unsigned long | DetectColorFaces (cv::Mat &img, std::vector< cv::Rect > &faceCoordinates) |
| virtual unsigned long | DetectFaces (cv::Mat &img, cv::Mat &rangeImg, std::vector< cv::Rect > &colorFaceCoordinates, std::vector< cv::Rect > &rangeFaceCoordinates, std::set< size_t > &colorToRangeFaceDependency, bool fillUnassignedDepthValues=false) |
| virtual unsigned long | DetectRangeFace (cv::Mat &img, std::vector< cv::Rect > &rangeFaceCoordinates, bool fillUnassignedDepthValues=false) |
| virtual unsigned long | Init (std::string directory) |
| virtual unsigned long | PCA (int *nEigens, std::vector< cv::Mat > &eigenVectors, cv::Mat &eigenValMat, cv::Mat &avgImage, std::vector< cv::Mat > &images, cv::Mat &projectedTrainFaceMat) |
| PeopleDetector (void) | |
| Constructor. | |
| virtual cv::Mat | preprocessImage (cv::Mat &input_image) |
| virtual unsigned long | RecognizeFace (cv::Mat &colorImage, std::vector< cv::Rect > &colorFaces, int *nEigens, std::vector< cv::Mat > &eigenVectArr, cv::Mat &avgImage, cv::Mat &projectedTrainFaceMat, std::vector< int > &index, int *threshold, int *threshold_FS, cv::Mat &eigenValMat, cv::ml::SVM *personClassifier=0) |
| ~PeopleDetector (void) | |
| Destructor. | |
Public Attributes | |
| int | m_faces_drop_groups |
| Minimum number (minus 1) of neighbor rectangles that makes up an object. | |
| double | m_faces_increase_search_scale |
| The factor by which the search window is scaled between the subsequent scans. | |
| int | m_faces_min_search_scale_x |
| Minimum search scale x. | |
| int | m_faces_min_search_scale_y |
| Minimum search scale y. | |
| int | m_range_drop_groups |
| Minimum number (minus 1) of neighbor rectangles that makes up an object. | |
| double | m_range_increase_search_scale |
| The factor by which the search window is scaled between the subsequent scans. | |
| int | m_range_min_search_scale_x |
| Minimum search scale x. | |
| int | m_range_min_search_scale_y |
| Minimum search scale y. | |
Private Member Functions | |
| unsigned long | InterpolateUnassignedPixels (cv::Mat &img) |
Private Attributes | |
| CvHaarClassifierCascade * | m_face_cascade |
| Haar-Classifier for face-detection. | |
| CvHaarClassifierCascade * | m_range_cascade |
| Haar-Classifier for range-detection. | |
| CvMemStorage * | m_storage |
| Storage for face and eye detection. | |
Interface to Calibrate Head of Care-O-bot 3. Long description
Definition at line 24 of file people_detector.h.
| PeopleDetector::PeopleDetector | ( | void | ) |
| PeopleDetector::~PeopleDetector | ( | void | ) |
Destructor.
Definition at line 37 of file people_detector.cpp.
| unsigned long PeopleDetector::AddFace | ( | cv::Mat & | img, |
| cv::Rect & | face, | ||
| std::string | id, | ||
| std::vector< cv::Mat > & | images, | ||
| std::vector< std::string > & | ids | ||
| ) | [virtual] |
Function to add a new face The function adds a new face to the trained images
| img | Image |
| face | The face |
| id | Id of the new face |
| images | Vector with trained images |
| ids | Vector with trained ids |
Definition at line 198 of file people_detector.cpp.
| unsigned long PeopleDetector::CalculateFaceClasses | ( | cv::Mat & | projectedTrainFaceMat, |
| std::vector< std::string > & | id, | ||
| int * | nEigens, | ||
| cv::Mat & | faceClassAvgProjections, | ||
| std::vector< std::string > & | idUnique, | ||
| cv::ml::SVM * | personClassifier = 0 |
||
| ) | [virtual] |
Function to calculate the FaceClasses The function calculates the average eigenvector decomposition factors for each face classes.
| projectedTrainFaceMat | The projected training faces |
| id | The ids of the training faces |
| nEigens | Number of eigenvalues |
| faceClassAvgProjections | The average factors of the eigenvector decomposition from each face class |
| idUnique | A vector containing all different Ids from the training session exactly once (idUnique[i] stores the corresponding id to the average face coordinates in the face subspace in faceClassAvgProjections.row(i)) |
| personClassifier | A classifier for person identification. It is trained in this function. Can be left out if a simpler identification method is used. |
Definition at line 497 of file people_detector.cpp.
| unsigned long PeopleDetector::ClassifyFace | ( | float * | projectedTestFace, |
| int * | nearest, | ||
| int * | nEigens, | ||
| cv::Mat & | projectedTrainFaceMat, | ||
| int * | threshold, | ||
| cv::Mat & | eigenValMat, | ||
| cv::ml::SVM * | personClassifier = 0 |
||
| ) | [virtual] |
Function to find the closest face class The function calculates the distance of each sample image to the trained face class
| projectedTestFace | The projected test face |
| nearest | Index of nearest face, or -1 if the face is unknown |
| nEigens | Number of eigenvalues |
| projectedTrainFaceMat | The average factors from each face class originating from the eigenvector decomposition |
| threshold | The threshold to recognize unkown faces |
| eigenValMat | Eigenvalues |
| personClassifier | A classifier for person identification. It is trained in this function. Can be left out if a simpler identification method is used. |
Definition at line 423 of file people_detector.cpp.
| unsigned long PeopleDetector::ConvertAndResize | ( | cv::Mat & | img, |
| cv::Mat & | resized, | ||
| cv::Rect & | face | ||
| ) | [virtual] |
Function to Convert and Resizes a given image The function converts a 8U3 image from camera to an 8U1 image and resizes the face to 100x100 px.
| img | Image from camera |
| resized | Resized image from face |
| face | The face |
Definition at line 211 of file people_detector.cpp.
| unsigned long PeopleDetector::DetectColorFaces | ( | cv::Mat & | img, |
| std::vector< cv::Rect > & | faceCoordinates | ||
| ) | [virtual] |
Function to detect the faces on color image The function detects the faces in an given image
| img | Image |
| faceCoordinates | Vector with the coordinates of detected faces in color image |
Definition at line 45 of file people_detector.cpp.
| unsigned long PeopleDetector::DetectFaces | ( | cv::Mat & | img, |
| cv::Mat & | rangeImg, | ||
| std::vector< cv::Rect > & | colorFaceCoordinates, | ||
| std::vector< cv::Rect > & | rangeFaceCoordinates, | ||
| std::set< size_t > & | colorToRangeFaceDependency, | ||
| bool | fillUnassignedDepthValues = false |
||
| ) | [virtual] |
Function to detect faces The function calls internally the functions DetectRangeFace() and DetectColorFaces()
| img | Color image |
| rangeImg | Range image |
| faceCoordinates | Vector with the coordinates of detected faces on complete color image |
| rangeFaceCoordinates | Vector with the coordinates of heads on range image |
| colorToRangeFaceDependency | stores the indices of range images that contain a face detection in the color image |
| fillUnassignedDepthValues | this parameter should be true if the kinect sensor is used (activates a filling method for black pixels) |
Definition at line 131 of file people_detector.cpp.
| unsigned long PeopleDetector::DetectRangeFace | ( | cv::Mat & | img, |
| std::vector< cv::Rect > & | rangeFaceCoordinates, | ||
| bool | fillUnassignedDepthValues = false |
||
| ) | [virtual] |
Function to detect the face on range image The function detects the face in an given range image
| img | Image |
| rangeFaceCoordinates | Vector with the 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 109 of file people_detector.cpp.
| unsigned long PeopleDetector::Init | ( | std::string | directory | ) | [virtual] |
Initialization function. Creates an instance of a range imaging sensor (i.e. SwissRanger SR-3000) and an instance of
| directory | The directory for data files |
Definition at line 21 of file people_detector.cpp.
| unsigned long PeopleDetector::InterpolateUnassignedPixels | ( | cv::Mat & | img | ) | [private] |
interpolates unassigned pixels in the depth image when using the kinect
| img | depth image |
Definition at line 65 of file people_detector.cpp.
| unsigned long PeopleDetector::PCA | ( | int * | nEigens, |
| std::vector< cv::Mat > & | eigenVectors, | ||
| cv::Mat & | eigenValMat, | ||
| cv::Mat & | avgImage, | ||
| std::vector< cv::Mat > & | images, | ||
| cv::Mat & | projectedTrainFaceMat | ||
| ) | [virtual] |
Function to Run the PCA algorithm
| nEigens | Number of eigenvalues |
| eigenVectors | Eigenvectors |
| eigenValMat | Eigenvalues |
| avgImage | Average image |
| images | Trained faces |
| projectedTrainFaceMat | Projected training faces (coefficients for the eigenvectors of the face subspace) |
Definition at line 267 of file people_detector.cpp.
| cv::Mat PeopleDetector::preprocessImage | ( | cv::Mat & | input_image | ) | [virtual] |
Applies some preprocessing to the grayscale face images to obtain a more robust identification.
| input_image | Grayscale face image. |
Definition at line 221 of file people_detector.cpp.
| unsigned long PeopleDetector::RecognizeFace | ( | cv::Mat & | colorImage, |
| std::vector< cv::Rect > & | colorFaces, | ||
| int * | nEigens, | ||
| std::vector< cv::Mat > & | eigenVectArr, | ||
| cv::Mat & | avgImage, | ||
| cv::Mat & | projectedTrainFaceMat, | ||
| std::vector< int > & | index, | ||
| int * | threshold, | ||
| int * | threshold_FS, | ||
| cv::Mat & | eigenValMat, | ||
| cv::ml::SVM * | personClassifier = 0 |
||
| ) | [virtual] |
Function to Recognize faces The function recognize the faces
| colorImage | source color image |
| faceCoordinates | Detected faces |
| nEigens | Number of eigenvalues |
| eigenVectArr | Eigenvectors |
| avgImage | Average image |
| projectedTrainFaceMat | Projected training faces |
| index | Index of classified face in vector |
| threshold | The threshold to recognize unkown faces |
| threshold_FS | The threshold to the face space |
| eigenValMat | Eigenvalues |
| personClassifier | A classifier for person identification. It is trained in this function. Can be left out if a simpler identification method is used. |
Definition at line 339 of file people_detector.cpp.
CvHaarClassifierCascade* ipa_PeopleDetector::PeopleDetector::m_face_cascade [private] |
Haar-Classifier for face-detection.
Definition at line 170 of file people_detector.h.
Minimum number (minus 1) of neighbor rectangles that makes up an object.
Definition at line 154 of file people_detector.h.
The factor by which the search window is scaled between the subsequent scans.
Definition at line 153 of file people_detector.h.
Minimum search scale x.
Definition at line 155 of file people_detector.h.
Minimum search scale y.
Definition at line 156 of file people_detector.h.
CvHaarClassifierCascade* ipa_PeopleDetector::PeopleDetector::m_range_cascade [private] |
Haar-Classifier for range-detection.
Definition at line 171 of file people_detector.h.
Minimum number (minus 1) of neighbor rectangles that makes up an object.
Definition at line 159 of file people_detector.h.
The factor by which the search window is scaled between the subsequent scans.
Definition at line 158 of file people_detector.h.
Minimum search scale x.
Definition at line 160 of file people_detector.h.
Minimum search scale y.
Definition at line 161 of file people_detector.h.
CvMemStorage* ipa_PeopleDetector::PeopleDetector::m_storage [private] |
Storage for face and eye detection.
Definition at line 169 of file people_detector.h.