Public Member Functions | Public Attributes | Private Member Functions | Private Attributes
ipa_PeopleDetector::PeopleDetector Class Reference

#include <people_detector.h>

List of all members.

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::SVM *personClassifier=0)
virtual unsigned long ClassifyFace (float *projectedTestFace, int *nearest, int *nEigens, cv::Mat &projectedTrainFaceMat, int *threshold, cv::Mat &eigenValMat, cv::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::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.

Detailed Description

Interface to Calibrate Head of Care-O-bot 3. Long description

Definition at line 25 of file people_detector.h.


Constructor & Destructor Documentation

Constructor.

Constructor

Definition at line 16 of file people_detector.cpp.

Destructor.

Definition at line 38 of file people_detector.cpp.


Member Function Documentation

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

Parameters:
imgImage
faceThe face
idId of the new face
imagesVector with trained images
idsVector with trained ids
Returns:
Return code

Definition at line 199 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::SVM *  personClassifier = 0 
) [virtual]

Function to calculate the FaceClasses The function calculates the average eigenvector decomposition factors for each face classes.

Parameters:
projectedTrainFaceMatThe projected training faces
idThe ids of the training faces
nEigensNumber of eigenvalues
faceClassAvgProjectionsThe average factors of the eigenvector decomposition from each face class
idUniqueA 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))
personClassifierA classifier for person identification. It is trained in this function. Can be left out if a simpler identification method is used.
Returns:
Return code

Definition at line 481 of file people_detector.cpp.

unsigned long PeopleDetector::ClassifyFace ( float *  projectedTestFace,
int *  nearest,
int *  nEigens,
cv::Mat &  projectedTrainFaceMat,
int *  threshold,
cv::Mat &  eigenValMat,
cv::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

Parameters:
projectedTestFaceThe projected test face
nearestIndex of nearest face, or -1 if the face is unknown
nEigensNumber of eigenvalues
projectedTrainFaceMatThe average factors from each face class originating from the eigenvector decomposition
thresholdThe threshold to recognize unkown faces
eigenValMatEigenvalues
personClassifierA classifier for person identification. It is trained in this function. Can be left out if a simpler identification method is used.
Returns:
Return code

Definition at line 413 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.

Parameters:
imgImage from camera
resizedResized image from face
faceThe face
Returns:
Return code

Definition at line 212 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

Parameters:
imgImage
faceCoordinatesVector with the coordinates of detected faces in color image
Returns:
Return code

Definition at line 46 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()

Parameters:
imgColor image
rangeImgRange image
faceCoordinatesVector with the coordinates of detected faces on complete color image
rangeFaceCoordinatesVector with the coordinates of heads on range image
colorToRangeFaceDependencystores the indices of range images that contain a face detection in the color image
fillUnassignedDepthValuesthis parameter should be true if the kinect sensor is used (activates a filling method for black pixels)
Returns:
Return code

Definition at line 132 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

Parameters:
imgImage
rangeFaceCoordinatesVector with the coordinates of detected heads in range image
fillUnassignedDepthValuesthis parameter should be true if the kinect sensor is used (activates a filling method for black pixels)
Returns:
Return code

Definition at line 110 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

Parameters:
directoryThe directory for data files
Returns:
Return code

Definition at line 22 of file people_detector.cpp.

unsigned long PeopleDetector::InterpolateUnassignedPixels ( cv::Mat &  img) [private]

interpolates unassigned pixels in the depth image when using the kinect

Parameters:
imgdepth image
Returns:
Return code

Definition at line 66 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

Parameters:
nEigensNumber of eigenvalues
eigenVectorsEigenvectors
eigenValMatEigenvalues
avgImageAverage image
imagesTrained faces
projectedTrainFaceMatProjected training faces (coefficients for the eigenvectors of the face subspace)
Returns:
Return code

Definition at line 268 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.

Parameters:
input_imageGrayscale face image.
Returns:
Preprocessed image.

Definition at line 222 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::SVM *  personClassifier = 0 
) [virtual]

Function to Recognize faces The function recognize the faces

Parameters:
colorImagesource color image
faceCoordinatesDetected faces
nEigensNumber of eigenvalues
eigenVectArrEigenvectors
avgImageAverage image
projectedTrainFaceMatProjected training faces
indexIndex of classified face in vector
thresholdThe threshold to recognize unkown faces
threshold_FSThe threshold to the face space
eigenValMatEigenvalues
personClassifierA classifier for person identification. It is trained in this function. Can be left out if a simpler identification method is used.
Returns:
Return code

Definition at line 335 of file people_detector.cpp.


Member Data Documentation

CvHaarClassifierCascade* ipa_PeopleDetector::PeopleDetector::m_face_cascade [private]

Haar-Classifier for face-detection.

Definition at line 155 of file people_detector.h.

Minimum number (minus 1) of neighbor rectangles that makes up an object.

Definition at line 139 of file people_detector.h.

The factor by which the search window is scaled between the subsequent scans.

Definition at line 138 of file people_detector.h.

Minimum search scale x.

Definition at line 140 of file people_detector.h.

Minimum search scale y.

Definition at line 141 of file people_detector.h.

CvHaarClassifierCascade* ipa_PeopleDetector::PeopleDetector::m_range_cascade [private]

Haar-Classifier for range-detection.

Definition at line 156 of file people_detector.h.

Minimum number (minus 1) of neighbor rectangles that makes up an object.

Definition at line 144 of file people_detector.h.

The factor by which the search window is scaled between the subsequent scans.

Definition at line 143 of file people_detector.h.

Minimum search scale x.

Definition at line 145 of file people_detector.h.

Minimum search scale y.

Definition at line 146 of file people_detector.h.

Storage for face and eye detection.

Definition at line 154 of file people_detector.h.


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


cob_people_detection
Author(s): Richard Bormann , Thomas Zwölfer
autogenerated on Fri Aug 28 2015 10:24:13