Classes | Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes
FaceNormalizer Class Reference

#include <face_normalizer.h>

List of all members.

Classes

struct  FNConfig
 Face normalizer configuration struct. More...

Public Member Functions

bool eliminate_background (cv::Mat &RGB, cv::Mat &XYZ, float background_thresh)
 FaceNormalizer ()
 Constructor for face normalizer.
void init ()
 Default initialization.
void init (FNConfig &i_config)
 Initialization with given config.
void init (std::string i_classifier_directory, FNConfig &i_config)
 Initialization with given config and path for haar classifier cascades.
void init (std::string i_classifier_directory, std::string i_storage_directory, FNConfig &i_config, int i_epoch_ctr, bool i_debug, bool i_record_scene)
 Initialization with full control of behavior.
bool interpolate_head (cv::Mat &RGB, cv::Mat &XYZ)
bool isolateFace (cv::Mat &RGB, cv::Mat &XYZ)
bool normalizeFace (cv::Mat &RGB, cv::Size &norm_size)
 Function to normalize a color image.
bool normalizeFace (cv::Mat &RGB, cv::Mat &XYZ, cv::Size &norm_size, cv::Mat &DM)
 Function to obtain normalized color image and depth map.
bool normalizeFace (cv::Mat &RGB, cv::Mat &XYZ, cv::Size &norm_size)
 Function to normalize a color image and point cloud.
bool read_scene (cv::Mat &RGB, cv::Mat &XYZ, std::string path)
 Function to read scene.
bool recordFace (cv::Mat &RGB, cv::Mat &XYZ)
bool save_scene (cv::Mat &RGB, cv::Mat &XYZ, std::string path)
 Function to save scene.
bool synth_head_poses (cv::Mat &img, cv::Mat &depth, std::vector< cv::Mat > &synth_images)
bool synth_head_poses_relative (cv::Mat &img, cv::Mat &depth, std::vector< cv::Mat > &synth_images)
bool synthFace (cv::Mat &RGB, cv::Mat &XYZ, cv::Size &norm_size, std::vector< cv::Mat > &synth_images)
 Function to synthetisize artificial poses from one image.
 ~FaceNormalizer ()
 Destructor for face normalizer.

Public Attributes

FNConfig config_
 Configuration of face normalizer.

Protected Member Functions

void create_DM (cv::Mat &XYZ, cv::Mat &DM)
 Function creates depth map from point cloud.
template<class T >
void despeckle (cv::Mat &src, cv::Mat &dst)
 Function fill gaps in image.
bool detect_feature (cv::Mat &img, cv::Point2f &coords, FACE::FEATURE_TYPE type)
 Function detects specified facial feature in color image.
void dump_features (cv::Mat &img)
 Function to save image with detected features.
void dump_img (cv::Mat &data, std::string name)
 Function to save image under given path.
void extractVChannel (cv::Mat &img, cv::Mat &V)
 Function to extract value channel.
bool features_from_color (cv::Mat &img)
 Function detects facial features in color image.
bool features_from_depth (cv::Mat &depth)
 Function picks 3D coordinates of facial features.
void GammaDCT (cv::Mat &img)
 Function for illumination normalization with Gamma DCT.
void GammaDoG (cv::Mat &img)
 Function for illumination normalization with Gamma DCT.
bool normalize_geometry_depth (cv::Mat &img, cv::Mat &depth)
 Function for geometric normalization.
bool normalize_img_type (cv::Mat &in, cv::Mat &out)
bool normalize_radiometry (cv::Mat &img)
 Function for illumination normalization.
bool projectPoint (cv::Point3f &xyz, cv::Point2f &uv)
 Function projects point to image plane.
bool projectPointCloud (cv::Mat &RGB, cv::Mat &XYZ, cv::Mat &img_res, cv::Mat &depth_res)
 Function projects point cloud on image plane.
bool rotate_head (cv::Mat &img, cv::Mat &depth)
 Function for artificial head poses.
void subVChannel (cv::Mat &img, cv::Mat &V)
 Function to substitute value channel in color image.

Protected Attributes

cv::Mat cam_mat_
 Camera matrix used for projection to image plane.
std::string classifier_directory_
 Directory where haarcascade classifiers are stored.
bool debug_
 Flag activates debug outbput.
cv::Mat dist_coeffs_
 Distortion coefficients for camera model.
int epoch_ctr_
 Counter for input frames.
CvHaarClassifierCascade * eye_l_cascade_
 OpenCv haarclassifier cascade for left eye.
CvMemStorage * eye_l_storage_
 Pointer to OpenCv memory storage.
CvHaarClassifierCascade * eye_r_cascade_
 OpenCv haarclassifier cascade for right eye.
CvMemStorage * eye_r_storage_
 Pointer to OpenCv memory storage.
FACE::FaceFeatures< cv::Point2f > f_det_img_
 Facial features detected in color image.
FACE::FaceFeatures< cv::Point3f > f_det_xyz_
 Facial features detected in point cloud.
bool initialized_
 Flag indicating if face normalizer is already initialized.
cv::Size input_size_
 Size of input image.
cv::Size norm_size_
 Norm size the image is scaled to.
CvHaarClassifierCascade * nose_cascade_
 OpenCv haarclassifier cascade for nose.
CvMemStorage * nose_storage_
 Pointer to OpenCv memory storage.
bool record_scene_
 Flag indicates whether scene is recorded.
std::string storage_directory_
 Directory where debug information is saved.

Detailed Description

Definition at line 112 of file face_normalizer.h.


Constructor & Destructor Documentation

Constructor for face normalizer.

Definition at line 131 of file face_normalizer.h.

Destructor for face normalizer.

Definition at line 92 of file face_normalizer.cpp.


Member Function Documentation

void FaceNormalizer::create_DM ( cv::Mat &  XYZ,
cv::Mat &  DM 
) [protected]

Function creates depth map from point cloud.

The function creates normalized depth map from point cloud..

Parameters:
[in]XYZInput 3D point cloud.
[out]DMOutput normalized depth map.

Definition at line 1279 of file face_normalizer.cpp.

template<class T >
void FaceNormalizer::despeckle ( cv::Mat &  src,
cv::Mat &  dst 
) [inline, protected]

Function fill gaps in image.

The uses interpolation to close gaps without color information. It can be used for images consisting of one or three channels.

Parameters:
[in]srcInput image.
outdst Output image.

Definition at line 357 of file face_normalizer.h.

bool FaceNormalizer::detect_feature ( cv::Mat &  img,
cv::Point2f &  coords,
FACE::FEATURE_TYPE  type 
) [protected]

Function detects specified facial feature in color image.

The function detects specific facial feature.

Parameters:
[in]imgColor image containing facial features.
[out]coordsImage coordinates of detected facial feature.
[in]typeFeature type that is supposed t be detected.
Returns:
Return true/false whether feature could be detected.

Definition at line 1156 of file face_normalizer.cpp.

void FaceNormalizer::dump_features ( cv::Mat &  img) [protected]

Function to save image with detected features.

The function saves color image with marked detected facial features for debug puroposes.

Parameters:
[in,out]imgColor image which is saved.

Definition at line 1237 of file face_normalizer.cpp.

void FaceNormalizer::dump_img ( cv::Mat &  data,
std::string  name 
) [protected]

Function to save image under given path.

The function saves a given image under the specified path.

Parameters:
[in,out]imgColor image which is saved.

Definition at line 1220 of file face_normalizer.cpp.

bool FaceNormalizer::eliminate_background ( cv::Mat &  RGB,
cv::Mat &  XYZ,
float  background_thresh 
)

Definition at line 1482 of file face_normalizer.cpp.

void FaceNormalizer::extractVChannel ( cv::Mat &  img,
cv::Mat &  V 
) [protected]

Function to extract value channel.

The function extracts the value channel in the HSV colorspace of a RGB image.

Parameters:
[in]imgColor image where value channel is extracted.
[out]VValue channel of HSV representation of input image.
Returns:
true when process was successful

Definition at line 312 of file face_normalizer.cpp.

bool FaceNormalizer::features_from_color ( cv::Mat &  img) [protected]

Function detects facial features in color image.

The function detects facial features (nose, eyes) in color image.

Parameters:
[in]imgColor image containing facial features.
Returns:
Return true/false whether all features could be detected.

Definition at line 1104 of file face_normalizer.cpp.

bool FaceNormalizer::features_from_depth ( cv::Mat &  depth) [protected]

Function picks 3D coordinates of facial features.

The function picks coordinates of facial features (nose, eyes) in point cloud.

Parameters:
[in]XYZInput point cloud.
Returns:
Return true/false whether valid coordinates could be picked.

Definition at line 1135 of file face_normalizer.cpp.

void FaceNormalizer::GammaDCT ( cv::Mat &  img) [protected]

Function for illumination normalization with Gamma DCT.

The function performs illumination normalization with the Gamma DCT method. This method is recommended for most cases.

Parameters:
[in,out]imgColor image which is normalized.
Returns:
true when process was successful

Definition at line 377 of file face_normalizer.cpp.

void FaceNormalizer::GammaDoG ( cv::Mat &  img) [protected]

Function for illumination normalization with Gamma DCT.

The function performs illumination normalization with the Gamma DoG method. This method is recommended for extreme cases. It can be activated during initialization with configuration for extreme illumination conditions.

See also:
FNConfig
Parameters:
[in,out]imgColor image which is normalized.
Returns:
true when process was successful

Definition at line 347 of file face_normalizer.cpp.

Default initialization.

The function inititializes the face normalizer with default values.

Definition at line 34 of file face_normalizer.cpp.

void FaceNormalizer::init ( FNConfig i_config)

Initialization with given config.

The function initializes the face normalizer with given config.

Parameters:
[in]i_configConfiguration for face normalizer.

Definition at line 18 of file face_normalizer.cpp.

void FaceNormalizer::init ( std::string  i_classifier_directory,
FNConfig i_config 
)

Initialization with given config and path for haar classifier cascades.

The function initializes the face normalizer with directory for haar cascades and given config.

Parameters:
[in]i_classifier_directoryDirectory where haar classifier cascades are stored.
[in]i_configConfiguration for face normalizer.

Definition at line 24 of file face_normalizer.cpp.

void FaceNormalizer::init ( std::string  i_classifier_directory,
std::string  i_storage_directory,
FNConfig i_config,
int  i_epoch_ctr,
bool  i_debug,
bool  i_record_scene 
)

Initialization with full control of behavior.

The function initializes the face normalizer with all option.

Parameters:
[in]i_classifier_directoryDirectory where haar classifier cascades are stored.
[in]i_storage_directoryDirectory where debug output is saved.
[in]i_configConfiguration for face normalizer.
[in]i_epoch_ctrStarting number for input frames.
[in]i_debugFlag whether debug output is printed.
[in]i_record_sceneFlag whether scene is saved automatically.

Definition at line 52 of file face_normalizer.cpp.

bool FaceNormalizer::interpolate_head ( cv::Mat &  RGB,
cv::Mat &  XYZ 
)

Definition at line 1521 of file face_normalizer.cpp.

bool FaceNormalizer::isolateFace ( cv::Mat &  RGB,
cv::Mat &  XYZ 
)

Definition at line 105 of file face_normalizer.cpp.

bool FaceNormalizer::normalize_geometry_depth ( cv::Mat &  img,
cv::Mat &  depth 
) [protected]

Function for geometric normalization.

The function normalizes image geometry using xyz information.

Parameters:
[in,out]imgColor image that is normalized.
[in,out]depthPointcloud that is normalized.
Returns:
Return true/false whether geometric normalization was successful.

Definition at line 991 of file face_normalizer.cpp.

bool FaceNormalizer::normalize_img_type ( cv::Mat &  in,
cv::Mat &  out 
) [protected]

This function is called to ensure image return type consistency

Parameters:
[in]ininput image
[out]outoutput image
Returns:
true when process was successful

Definition at line 1532 of file face_normalizer.cpp.

bool FaceNormalizer::normalize_radiometry ( cv::Mat &  img) [protected]

Function for illumination normalization.

The function normalizes image illumination using GammaDCT or GammaDoG algorithms.

Parameters:
[in,out]imgColor image that is normalized.
Returns:
Return true/false whether illumination normalization was successful.

Definition at line 304 of file face_normalizer.cpp.

bool FaceNormalizer::normalizeFace ( cv::Mat &  RGB,
cv::Size &  norm_size 
)

Function to normalize a color image.

The function normalizes given color image with respect to illumination and size.

Parameters:
[in,out]RGBColor image that is normalized.
[in]norm_sizeSize the input image is scaled to.
Returns:
Return true/false whether normalization was successful.

Definition at line 261 of file face_normalizer.cpp.

bool FaceNormalizer::normalizeFace ( cv::Mat &  RGB,
cv::Mat &  XYZ,
cv::Size &  norm_size,
cv::Mat &  DM 
)

Function to obtain normalized color image and depth map.

The function normalizes given color image with the corresponding point cloud respect to illumination and size and recording perspective

Parameters:
[in,out]RGBColor image that is normalized
[in]XYZPointcloud corresponding to color image
[in]norm_sizeSize the input image is scaled to
[out]DMDepth map generated from normalized point cloud
Returns:
Return true/false whether normalization was successful

Definition at line 184 of file face_normalizer.cpp.

bool FaceNormalizer::normalizeFace ( cv::Mat &  RGB,
cv::Mat &  XYZ,
cv::Size &  norm_size 
)

Function to normalize a color image and point cloud.

The function normalizes given color image with the corresponding point cloud respect to illumination and size and recording perspective.

Parameters:
[in,out]RGBColor image that is normalized.
[in]XYZPointcloud corresponding to color image.
[in]norm_sizeSize the input image is scaled to.
Returns:
Return true/false whether normalization was successful.

Definition at line 195 of file face_normalizer.cpp.

bool FaceNormalizer::projectPoint ( cv::Point3f &  xyz,
cv::Point2f &  uv 
) [protected]

Function projects point to image plane.

The function projects XYZ information of point to image plane.

Parameters:
[in]xyzInput 3D point.
[out]uvOutput 2D image point.
[out]depth_resResulting projected depth image.
Returns:
Return true/false whether projection was successful.

Definition at line 1316 of file face_normalizer.cpp.

bool FaceNormalizer::projectPointCloud ( cv::Mat &  RGB,
cv::Mat &  XYZ,
cv::Mat &  img_res,
cv::Mat &  depth_res 
) [protected]

Function projects point cloud on image plane.

The function projects RGB and XYZ information of given image and point cloud to image plane.

Parameters:
[in]RGBColor image.
[in]XYZInput point cloud.
[out]img_resResulting projected image.
[out]depth_resResulting projected depth image.
Returns:
Return true/false whether projection was successful.

Definition at line 1327 of file face_normalizer.cpp.

bool FaceNormalizer::read_scene ( cv::Mat &  RGB,
cv::Mat &  XYZ,
std::string  path 
)

Function to read scene.

The function reads scene, consisting of color image and corresponding point cloud from given path.

Parameters:
[out]RGBColor image that is normalized.
[out]XYZPointcloud corresponding to color image.
Returns:
Return true/false whether reading was successful.

Definition at line 1268 of file face_normalizer.cpp.

bool FaceNormalizer::recordFace ( cv::Mat &  RGB,
cv::Mat &  XYZ 
)

Definition at line 116 of file face_normalizer.cpp.

bool FaceNormalizer::rotate_head ( cv::Mat &  img,
cv::Mat &  depth 
) [protected]

Function for artificial head poses.

The function manufactures artificial head poses

Parameters:
[in,out]imgColor image that is normalized.
[in,out]depthPointcloud that is normalized.
Returns:
Return true/false whether rotation was successful.

Definition at line 819 of file face_normalizer.cpp.

bool FaceNormalizer::save_scene ( cv::Mat &  RGB,
cv::Mat &  XYZ,
std::string  path 
)

Function to save scene.

The function saves scene, consisting of color image and corresponding point cloud to given path.

Parameters:
[in]RGBColor image that is normalized.
[in]XYZPointcloud corresponding to color image.
Returns:
Return true/false whether saving was successful.

Definition at line 1250 of file face_normalizer.cpp.

void FaceNormalizer::subVChannel ( cv::Mat &  img,
cv::Mat &  V 
) [protected]

Function to substitute value channel in color image.

The function substitutes the value channel in the HSV colorspace of a RGB image with a given image.

Parameters:
[in,out]imgColor image where value channel is substituted.
[in]VValue channel.

Definition at line 328 of file face_normalizer.cpp.

bool FaceNormalizer::synth_head_poses ( cv::Mat &  img,
cv::Mat &  depth,
std::vector< cv::Mat > &  synth_images 
)

Definition at line 622 of file face_normalizer.cpp.

bool FaceNormalizer::synth_head_poses_relative ( cv::Mat &  img,
cv::Mat &  depth,
std::vector< cv::Mat > &  synth_images 
)

Definition at line 443 of file face_normalizer.cpp.

bool FaceNormalizer::synthFace ( cv::Mat &  RGB,
cv::Mat &  XYZ,
cv::Size &  norm_size,
std::vector< cv::Mat > &  synth_images 
)

Function to synthetisize artificial poses from one image.

Definition at line 126 of file face_normalizer.cpp.


Member Data Documentation

cv::Mat FaceNormalizer::cam_mat_ [protected]

Camera matrix used for projection to image plane.

Definition at line 332 of file face_normalizer.h.

std::string FaceNormalizer::classifier_directory_ [protected]

Directory where haarcascade classifiers are stored.

Definition at line 329 of file face_normalizer.h.

Configuration of face normalizer.

Definition at line 212 of file face_normalizer.h.

bool FaceNormalizer::debug_ [protected]

Flag activates debug outbput.

Definition at line 325 of file face_normalizer.h.

cv::Mat FaceNormalizer::dist_coeffs_ [protected]

Distortion coefficients for camera model.

Definition at line 333 of file face_normalizer.h.

int FaceNormalizer::epoch_ctr_ [protected]

Counter for input frames.

Definition at line 324 of file face_normalizer.h.

CvHaarClassifierCascade* FaceNormalizer::eye_l_cascade_ [protected]

OpenCv haarclassifier cascade for left eye.

Definition at line 338 of file face_normalizer.h.

CvMemStorage* FaceNormalizer::eye_l_storage_ [protected]

Pointer to OpenCv memory storage.

Definition at line 339 of file face_normalizer.h.

CvHaarClassifierCascade* FaceNormalizer::eye_r_cascade_ [protected]

OpenCv haarclassifier cascade for right eye.

Definition at line 341 of file face_normalizer.h.

CvMemStorage* FaceNormalizer::eye_r_storage_ [protected]

Pointer to OpenCv memory storage.

Definition at line 342 of file face_normalizer.h.

Facial features detected in color image.

Definition at line 344 of file face_normalizer.h.

Facial features detected in point cloud.

Definition at line 345 of file face_normalizer.h.

bool FaceNormalizer::initialized_ [protected]

Flag indicating if face normalizer is already initialized.

Definition at line 323 of file face_normalizer.h.

cv::Size FaceNormalizer::input_size_ [protected]

Size of input image.

Definition at line 348 of file face_normalizer.h.

cv::Size FaceNormalizer::norm_size_ [protected]

Norm size the image is scaled to.

Definition at line 347 of file face_normalizer.h.

CvHaarClassifierCascade* FaceNormalizer::nose_cascade_ [protected]

OpenCv haarclassifier cascade for nose.

Definition at line 335 of file face_normalizer.h.

CvMemStorage* FaceNormalizer::nose_storage_ [protected]

Pointer to OpenCv memory storage.

Definition at line 336 of file face_normalizer.h.

Flag indicates whether scene is recorded.

Definition at line 326 of file face_normalizer.h.

std::string FaceNormalizer::storage_directory_ [protected]

Directory where debug information is saved.

Definition at line 328 of file face_normalizer.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