$search

ipa_PeopleDetector::PeopleDetectorControlFlow Class Reference

Long description. More...

#include <PeopleDetectorControlFlow.h>

List of all members.

Public Member Functions

unsigned long AddFace (cv::Mat &image, std::string id)
unsigned long DetectFaces (ipa_SensorFusion::ColoredPointCloudPtr pc)
unsigned long GetEigenface (cv::Mat &eigenface, int index)
ColoredPointCloudToolbox::t_PointCloudMode GetPCMode ()
unsigned long Init (std::string directory, ipa_CameraSensors::AbstractColorCameraPtr *colorCamera0=0, ipa_CameraSensors::AbstractColorCameraPtr *colorCamera1=0, ipa_CameraSensors::AbstractRangeImagingSensorPtr *rangeImagingSensor=0)
unsigned long LoadParameters (const char *iniFileName)
unsigned long LoadTrainingData ()
unsigned long PCA ()
 PeopleDetectorControlFlow (void)
 Constructor.
unsigned long RecognizeFace (ipa_SensorFusion::ColoredPointCloudPtr pc, std::vector< int > &index)
unsigned long SaveRangeTrainImages (ipa_SensorFusion::ColoredPointCloudPtr pc)
unsigned long SaveTrainingData ()
unsigned long ShowAVGImage (cv::Mat &avgImage)
 ~PeopleDetectorControlFlow (void)
 Destructor.

Public Attributes

cv::Mat m_avgImage
 Trained average Image.
std::vector< cv::Rect > m_colorFaces
 Vector with detected faces.
cv::Mat m_eigenValMat
 Eigenvalues.
std::vector< cv::Mat > m_eigenVectors
 Eigenvectors.
cv::Mat m_faceClassAvgProjections
 The average factors of the eigenvector decomposition from each face class.
std::vector< cv::Mat > m_faceImages
 Trained face images.
std::vector< std::string > m_id
 Id of learned faces.
std::vector< std::string > m_idUnique
 A vector containing all different Ids from the training session exactly once (m_idUnique[i] stores the corresponding id to the average face coordinates in the face subspace in m_faceClassAvgProjections.row(i)).
int m_nEigens
 Number of eigenvalues.
int m_OpenGL
 1, if OpenGL viewer is used to vizualise point cloud
ipa_SensorFusion::ColoredPointCloudToolbox * m_pcToolbox
PeopleDetectorm_PeopleDetector
cv::Mat m_projectedTrainFaceMat
 Projected training faces (coefficients for the eigenvectors of the face subspace).
int m_RangeCamIterations
 One median image is created out of all images.
std::vector< cv::Rect > m_rangeFaces
 Vector with detected rangeFaces.
int m_threshold
 Threshold to detect unknown faces.
int m_threshold_FS
 Threshold to facespace.

Private Attributes

ipa_CameraSensors::AbstractColorCamera * m_ColorCamera0
ipa_CameraSensors::AbstractColorCamera * m_ColorCamera1
ipa_CameraSensors::CameraSensorToolbox * m_ColorSensor0Toolbox
 Camera toolbox.
ipa_CameraSensors::CameraSensorToolbox * m_ColorSensor1Toolbox
 Camera toolbox.
int m_filname
ipa_CameraSensors::AbstractRangeImagingSensor * m_RangeImagingSensor
int m_rangeSensorHeight
ipa_CameraSensors::CameraSensorToolbox * m_RangeSensorToolbox
 Camera toolbox.
int m_rangeSensorWidth
bool m_runPCA

Detailed Description

Long description.

Definition at line 36 of file PeopleDetectorControlFlow.h.


Constructor & Destructor Documentation

PeopleDetectorControlFlow::PeopleDetectorControlFlow ( void   ) 

Constructor.

Constructor

Definition at line 13 of file PeopleDetectorControlFlow.cpp.

PeopleDetectorControlFlow::~PeopleDetectorControlFlow ( void   ) 

Destructor.

Definition at line 19 of file PeopleDetectorControlFlow.cpp.


Member Function Documentation

unsigned long PeopleDetectorControlFlow::AddFace ( cv::Mat &  image,
std::string  id 
)

Function to add a new face

Parameters:
image ColorImage
id Id of the new face
Returns:
Return code

Definition at line 75 of file PeopleDetectorControlFlow.cpp.

unsigned long PeopleDetectorControlFlow::DetectFaces ( ipa_SensorFusion::ColoredPointCloudPtr  pc  ) 

Function to detect and verify faces

Parameters:
pc ColoredPointClowed with images
Returns:
Return code

Definition at line 59 of file PeopleDetectorControlFlow.cpp.

unsigned long PeopleDetectorControlFlow::GetEigenface ( cv::Mat &  eigenface,
int  index 
)

Function to show the eigenfaces. Only for debugging and development

Parameters:
eigenface Eigenface
index Index of the eigenface
Returns:
Return code.

Definition at line 333 of file PeopleDetectorControlFlow.cpp.

ColoredPointCloudToolbox::t_PointCloudMode ipa_PeopleDetector::PeopleDetectorControlFlow::GetPCMode (  )  [inline]

Returns the point cloud mode which was loaded from the .xml file

Returns:
point cloud mode

Definition at line 109 of file PeopleDetectorControlFlow.h.

unsigned long PeopleDetectorControlFlow::Init ( std::string  directory,
ipa_CameraSensors::AbstractColorCameraPtr *  colorCamera0 = 0,
ipa_CameraSensors::AbstractColorCameraPtr *  colorCamera1 = 0,
ipa_CameraSensors::AbstractRangeImagingSensorPtr *  rangeImagingSensor = 0 
)

Initialization function. Creates an instance of a range imaging sensor (i.e. SwissRanger SR-3000) and an instance of a color Camera (i.e. Imaging Source camera i.e. DBK 31AF03).

Parameters:
directory Directory of camera sensors initialization file.
colorCamera0 First color camera instance.
colorCamera1 Second color camera instance.
rangeImagingSensor Range imaging sensor instance.
Returns:
Return code

Definition at line 23 of file PeopleDetectorControlFlow.cpp.

unsigned long PeopleDetectorControlFlow::LoadParameters ( const char *  iniFileName  ) 

Function to load Parameters from Configuration File

Parameters:
iniFileName Filename of the Configuration File
Returns:
Return code.

Load parameters from file

Definition at line 444 of file PeopleDetectorControlFlow.cpp.

unsigned long PeopleDetectorControlFlow::LoadTrainingData (  ) 

Function to load the training data

Returns:
Return code.

Definition at line 231 of file PeopleDetectorControlFlow.cpp.

unsigned long PeopleDetectorControlFlow::PCA (  ) 

Function to Run the PCA algorithm and project the training images to the PCA subspace

Returns:
Return code

Definition at line 89 of file PeopleDetectorControlFlow.cpp.

unsigned long PeopleDetectorControlFlow::RecognizeFace ( ipa_SensorFusion::ColoredPointCloudPtr  pc,
std::vector< int > &  index 
)

Function to Recognize faces The function recognize the faces

Parameters:
pc ColoredPointClowed with images
index Index of classified facespace in vector
Returns:
Return code

Definition at line 130 of file PeopleDetectorControlFlow.cpp.

unsigned long PeopleDetectorControlFlow::SaveRangeTrainImages ( ipa_SensorFusion::ColoredPointCloudPtr  pc  ) 

Function to extract images for training range classifier

Parameters:
pc ColoredPointCloud with images
Returns:
Return code.

Definition at line 412 of file PeopleDetectorControlFlow.cpp.

unsigned long PeopleDetectorControlFlow::SaveTrainingData (  ) 

Function to save the training data

Returns:
Return code.

Definition at line 142 of file PeopleDetectorControlFlow.cpp.

unsigned long PeopleDetectorControlFlow::ShowAVGImage ( cv::Mat &  avgImage  ) 

Function to show the average image of all trained images

Parameters:
avgImage The average image
Returns:
Return code.

Definition at line 368 of file PeopleDetectorControlFlow.cpp.


Member Data Documentation

Trained average Image.

Definition at line 120 of file PeopleDetectorControlFlow.h.

ipa_CameraSensors::AbstractColorCamera* ipa_PeopleDetector::PeopleDetectorControlFlow::m_ColorCamera0 [private]

Definition at line 137 of file PeopleDetectorControlFlow.h.

ipa_CameraSensors::AbstractColorCamera* ipa_PeopleDetector::PeopleDetectorControlFlow::m_ColorCamera1 [private]

Definition at line 138 of file PeopleDetectorControlFlow.h.

Vector with detected faces.

Definition at line 127 of file PeopleDetectorControlFlow.h.

ipa_CameraSensors::CameraSensorToolbox* ipa_PeopleDetector::PeopleDetectorControlFlow::m_ColorSensor0Toolbox [private]

Camera toolbox.

Definition at line 141 of file PeopleDetectorControlFlow.h.

ipa_CameraSensors::CameraSensorToolbox* ipa_PeopleDetector::PeopleDetectorControlFlow::m_ColorSensor1Toolbox [private]

Camera toolbox.

Definition at line 142 of file PeopleDetectorControlFlow.h.

Eigenvalues.

Definition at line 119 of file PeopleDetectorControlFlow.h.

Eigenvectors.

Definition at line 118 of file PeopleDetectorControlFlow.h.

The average factors of the eigenvector decomposition from each face class.

Definition at line 122 of file PeopleDetectorControlFlow.h.

Trained face images.

Definition at line 113 of file PeopleDetectorControlFlow.h.

Definition at line 146 of file PeopleDetectorControlFlow.h.

Id of learned faces.

Definition at line 114 of file PeopleDetectorControlFlow.h.

A vector containing all different Ids from the training session exactly once (m_idUnique[i] stores the corresponding id to the average face coordinates in the face subspace in m_faceClassAvgProjections.row(i)).

Definition at line 115 of file PeopleDetectorControlFlow.h.

Number of eigenvalues.

Definition at line 117 of file PeopleDetectorControlFlow.h.

1, if OpenGL viewer is used to vizualise point cloud

Definition at line 130 of file PeopleDetectorControlFlow.h.

ipa_SensorFusion::ColoredPointCloudToolbox* ipa_PeopleDetector::PeopleDetectorControlFlow::m_pcToolbox

Definition at line 109 of file PeopleDetectorControlFlow.h.

Definition at line 124 of file PeopleDetectorControlFlow.h.

Projected training faces (coefficients for the eigenvectors of the face subspace).

Definition at line 121 of file PeopleDetectorControlFlow.h.

One median image is created out of all images.

Number of images per range camera shot

Definition at line 131 of file PeopleDetectorControlFlow.h.

Vector with detected rangeFaces.

Definition at line 128 of file PeopleDetectorControlFlow.h.

ipa_CameraSensors::AbstractRangeImagingSensor* ipa_PeopleDetector::PeopleDetectorControlFlow::m_RangeImagingSensor [private]

Definition at line 136 of file PeopleDetectorControlFlow.h.

Definition at line 145 of file PeopleDetectorControlFlow.h.

ipa_CameraSensors::CameraSensorToolbox* ipa_PeopleDetector::PeopleDetectorControlFlow::m_RangeSensorToolbox [private]

Camera toolbox.

Definition at line 140 of file PeopleDetectorControlFlow.h.

Definition at line 144 of file PeopleDetectorControlFlow.h.

Definition at line 134 of file PeopleDetectorControlFlow.h.

Threshold to detect unknown faces.

Definition at line 125 of file PeopleDetectorControlFlow.h.

Threshold to facespace.

Definition at line 126 of file PeopleDetectorControlFlow.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