$search

ipa_PeopleDetector::PeopleDetector Class Reference

#include <PeopleDetector.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 PeopleDetector.h.


Constructor & Destructor Documentation

PeopleDetector::PeopleDetector ( void   ) 

Constructor.

Constructor

Definition at line 16 of file PeopleDetector.cpp.

PeopleDetector::~PeopleDetector ( void   ) 

Destructor.

Definition at line 38 of file PeopleDetector.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:
img Image
face The face
id Id of the new face
images Vector with trained images
ids Vector with trained ids
Returns:
Return code

Definition at line 201 of file PeopleDetector.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:
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.
Returns:
Return code

Definition at line 466 of file PeopleDetector.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:
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.
Returns:
Return code

Definition at line 404 of file PeopleDetector.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:
img Image from camera
resized Resized image from face
face The face
Returns:
Return code

Definition at line 214 of file PeopleDetector.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:
img Image
faceCoordinates Vector with the coordinates of detected faces in color image
Returns:
Return code

Definition at line 46 of file PeopleDetector.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:
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)
Returns:
Return code

Definition at line 136 of file PeopleDetector.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:
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)
Returns:
Return code

Definition at line 107 of file PeopleDetector.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:
directory The directory for data files
Returns:
Return code

Definition at line 22 of file PeopleDetector.cpp.

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

interpolates unassigned pixels in the depth image when using the kinect

Parameters:
img depth image
Returns:
Return code

Definition at line 73 of file PeopleDetector.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:
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)
Returns:
Return code

Definition at line 267 of file PeopleDetector.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_image Grayscale face image.
Returns:
Preprocessed image.

Definition at line 224 of file PeopleDetector.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:
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.
Returns:
Return code

Definition at line 330 of file PeopleDetector.cpp.


Member Data Documentation

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

Haar-Classifier for face-detection.

Definition at line 155 of file PeopleDetector.h.

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

Definition at line 139 of file PeopleDetector.h.

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

Definition at line 138 of file PeopleDetector.h.

Minimum search scale x.

Definition at line 140 of file PeopleDetector.h.

Minimum search scale y.

Definition at line 141 of file PeopleDetector.h.

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

Haar-Classifier for range-detection.

Definition at line 156 of file PeopleDetector.h.

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

Definition at line 144 of file PeopleDetector.h.

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

Definition at line 143 of file PeopleDetector.h.

Minimum search scale x.

Definition at line 145 of file PeopleDetector.h.

Minimum search scale y.

Definition at line 146 of file PeopleDetector.h.

Storage for face and eye detection.

Definition at line 154 of file PeopleDetector.h.


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


cob_people_detection
Author(s): Richard Bormann
autogenerated on Tue Mar 5 11:50:14 2013