#include <face_detection.h>
Public Member Functions | |
unsigned long | addFace (cv::Mat &image, std::string id) |
CobFaceDetectionNodelet () | |
unsigned long | convertColorImageMessageToMat (const sensor_msgs::Image::ConstPtr &color_image_msg, cv_bridge::CvImageConstPtr &color_image_ptr, cv::Mat &color_image) |
unsigned long | convertPclMessageToMat (const sensor_msgs::PointCloud2::ConstPtr &shared_image_msg, cv::Mat &depth_image) |
unsigned long | detectFaces (cv::Mat &xyz_image, cv::Mat &color_image) |
unsigned long | getEigenface (cv::Mat &eigenface, int index) |
std::string | getLabel (int index) |
returns the ID string corresponding to index index | |
unsigned long | init () |
unsigned long | loadAllData () |
unsigned long | loadParameters (const char *iniFileName) |
unsigned long | loadRecognizerData () |
void | loadServerCallback (const cob_people_detection::LoadGoalConstPtr &goal) |
unsigned long | loadTrainingData (bool runPCA) |
void | onInit () |
Nodelet init function. | |
unsigned long | PCA () |
void | recognizeCallback (const sensor_msgs::PointCloud2::ConstPtr &shared_image_msg, const sensor_msgs::Image::ConstPtr &color_image_msg) |
Topic callback managing the treatment of incoming data. | |
unsigned long | recognizeFace (cv::Mat &color_image, std::vector< int > &index) |
void | recognizeServerCallback (const cob_people_detection::RecognizeGoalConstPtr &goal) |
Action server callback which manages the execution of the recognition functionality. | |
bool | recognizeServiceServerCallback (cob_people_detection::Recognition::Request &req, cob_people_detection::Recognition::Response &res) |
unsigned long | saveAllData () |
unsigned long | saveRangeTrainImages (cv::Mat &xyz_image) |
unsigned long | saveRecognizerData () |
void | saveServerCallback (const cob_people_detection::SaveGoalConstPtr &goal) |
unsigned long | saveTrainingData () |
unsigned long | showAVGImage (cv::Mat &avgImage) |
void | showServerCallback (const cob_people_detection::ShowGoalConstPtr &goal) |
void | trainCaptureSampleServerCallback (const cob_people_detection::TrainCaptureSampleGoalConstPtr &goal) |
void | trainContinuousCallback (const sensor_msgs::PointCloud2::ConstPtr &shared_image_msg, const sensor_msgs::Image::ConstPtr &color_image_msg) |
void | trainContinuousServerCallback (const cob_people_detection::TrainContinuousGoalConstPtr &goal) |
~CobFaceDetectionNodelet () | |
Protected Attributes | |
boost::timed_mutex | action_mutex_ |
secures write and read operations to varibales occupied_by_action_, etc. | |
cv::Mat | avg_image_ |
Trained average Image. | |
bool | capture_training_face_ |
can be set true by an action while in training mode. then an image is captured. | |
image_transport::SubscriberFilter | color_camera_image_sub_ |
Color camera image topic. | |
std::vector< cv::Rect > | color_faces_ |
Vector with detected faces. | |
ipa_SensorFusion::ColoredPointCloudPtr | colored_pc_ |
Storage for acquired colored point cloud. | |
std::string | current_training_id_ |
the ID of the current person who is trained | |
std::string | directory_ |
directory for the data files | |
bool | display_ |
enables debug output | |
bool | do_recognition_ |
does people identification if true, else it's just people detection | |
cv::Mat | eigen_val_mat_ |
Eigenvalues. | |
std::vector< cv::Mat > | eigen_vectors_ |
Eigenvectors (spanning the face space) | |
cv::Mat | face_class_avg_projections_ |
The average factors of the eigenvector decomposition from each face class. | |
image_transport::Publisher | face_detection_image_pub_ |
topic for publishing the image containing the faces | |
std::vector< cv::Mat > | face_images_ |
Trained face images. | |
ros::Publisher | face_position_publisher_ |
publisher for the positions of the detected faces | |
double | face_size_max_m_ |
in meters | |
double | face_size_min_m_ |
in meters | |
int | filename_ |
increasing number for files to save | |
bool | fill_unassigned_depth_values_ |
fills the unassigned depth values in the depth image, must be true for a kinect sensor | |
std::vector< std::string > | id_ |
Id of learned faces. | |
std::vector< std::string > | id_unique_ |
A vector containing all different Ids from the training session exactly once (id_unique_[i] stores the corresponding id to the average face coordinates in the face subspace in face_class_avg_projections_.row(i)) | |
image_transport::ImageTransport * | it_ |
LoadServer * | load_server_ |
double | max_face_z_m_ |
in meters | |
int | n_eigens_ |
Number of eigenvalues. | |
ros::NodeHandle | node_handle_ |
ROS node handle. | |
int | number_training_images_captured_ |
if the training is in continuous mode, this variable counts how many training images already have been collected for the current training job | |
bool | occupied_by_action_ |
must be set true as long as an action callback is running or while the continuous recognition or training mode is running | |
PeopleDetector * | people_detector_ |
People detector core code. | |
cv::SVM | person_classifier_ |
classifier for the identity of a person | |
cv::Mat | projected_train_face_mat_ |
Projected training faces (coefficients for the eigenvectors of the face subspace) | |
std::set< size_t > | range_face_indices_with_color_face_detection_ |
this set stores which range faces also had a face detection in the color image | |
std::vector< cv::Rect > | range_faces_ |
Vector with detected rangeFaces. | |
bool | reason_about_3dface_size_ |
if true, the 3d face size is determined and only faces with reasonable size are accepted | |
RecognizeServer * | recognize_server_ |
bool | recognize_server_running_ |
is true while the recognition module is running | |
ros::ServiceServer | recognize_service_server_ |
Service server to switch recognition on or off. | |
bool | run_pca_ |
has to run a PCA when the data was modified | |
SaveServer * | save_server_ |
message_filters::Subscriber < sensor_msgs::PointCloud2 > | shared_image_sub_ |
Shared xyz image and color image topic. | |
ShowServer * | show_server_ |
message_filters::Synchronizer < message_filters::sync_policies::ApproximateTime < sensor_msgs::PointCloud2, sensor_msgs::Image > > * | sync_pointcloud_ |
message_filters::Connection | sync_pointcloud_callback_connection_ |
int | threshold_ |
Threshold to detect unknown faces. | |
int | threshold_fs_ |
Threshold to facespace. | |
TrainCaptureSampleServer * | train_capture_sample_server_ |
TrainContinuousServer * | train_continuous_server_ |
bool | train_continuous_server_running_ |
is true while the continuous training display is running | |
Static Protected Attributes | |
static const double | FACE_SIZE_MAX_M = 0.35 |
static const double | FACE_SIZE_MIN_M = 0.12 |
static const double | MAX_FACE_Z_M = 8.0 |
Definition at line 143 of file face_detection.h.
Definition at line 80 of file face_detection.cpp.
Definition at line 100 of file face_detection.cpp.
unsigned long CobFaceDetectionNodelet::addFace | ( | cv::Mat & | image, |
std::string | id | ||
) |
Function to add a new face
image | Color image |
id | Id of the new face |
Definition at line 698 of file face_detection.cpp.
unsigned long CobFaceDetectionNodelet::convertColorImageMessageToMat | ( | const sensor_msgs::Image::ConstPtr & | color_image_msg, |
cv_bridge::CvImageConstPtr & | color_image_ptr, | ||
cv::Mat & | color_image | ||
) |
Definition at line 1152 of file face_detection.cpp.
unsigned long CobFaceDetectionNodelet::convertPclMessageToMat | ( | const sensor_msgs::PointCloud2::ConstPtr & | shared_image_msg, |
cv::Mat & | depth_image | ||
) |
Definition at line 1168 of file face_detection.cpp.
unsigned long CobFaceDetectionNodelet::detectFaces | ( | cv::Mat & | xyz_image, |
cv::Mat & | color_image | ||
) |
Function to detect and verify faces
xyz_image | Coordinate image with x,y,z coordinates in meters |
color_image | Color image |
Definition at line 557 of file face_detection.cpp.
unsigned long CobFaceDetectionNodelet::getEigenface | ( | cv::Mat & | eigenface, |
int | index | ||
) |
Function to show the eigenfaces. Only for debugging and development
eigenface | Eigenface |
index | Index of the eigenface |
Definition at line 1048 of file face_detection.cpp.
std::string CobFaceDetectionNodelet::getLabel | ( | int | index | ) | [inline] |
returns the ID string corresponding to index index
Definition at line 1191 of file face_detection.cpp.
unsigned long CobFaceDetectionNodelet::init | ( | void | ) |
unsigned long CobFaceDetectionNodelet::loadAllData | ( | ) |
Loads the training data as well as the recognizer data.
Definition at line 895 of file face_detection.cpp.
unsigned long CobFaceDetectionNodelet::loadParameters | ( | const char * | iniFileName | ) |
Load parameters from file
Definition at line 1551 of file face_detection.cpp.
unsigned long CobFaceDetectionNodelet::loadRecognizerData | ( | ) |
Function to load the recognizer data (eigenvectors, -values, average image, etc.)
Definition at line 968 of file face_detection.cpp.
void CobFaceDetectionNodelet::loadServerCallback | ( | const cob_people_detection::LoadGoalConstPtr & | goal | ) |
Definition at line 451 of file face_detection.cpp.
unsigned long CobFaceDetectionNodelet::loadTrainingData | ( | bool | runPCA | ) |
Function to load the training data (images, ids)
runPCA | Do a PCA after loading the files. Necessary if the eigenvector matrices etc. are not loaded as well. |
Definition at line 905 of file face_detection.cpp.
void CobFaceDetectionNodelet::onInit | ( | ) | [virtual] |
Nodelet init function.
Implements nodelet::Nodelet.
Definition at line 122 of file face_detection.cpp.
unsigned long CobFaceDetectionNodelet::PCA | ( | ) |
Function to Run the PCA algorithm and project the training images to the PCA subspace
Definition at line 712 of file face_detection.cpp.
void CobFaceDetectionNodelet::recognizeCallback | ( | const sensor_msgs::PointCloud2::ConstPtr & | shared_image_msg, |
const sensor_msgs::Image::ConstPtr & | color_image_msg | ||
) |
Topic callback managing the treatment of incoming data.
Definition at line 1214 of file face_detection.cpp.
unsigned long CobFaceDetectionNodelet::recognizeFace | ( | cv::Mat & | color_image, |
std::vector< int > & | index | ||
) |
Function to Recognize faces The function recognize the faces
color_image | Color image |
index | Index of classified facespace in vector |
Definition at line 685 of file face_detection.cpp.
void CobFaceDetectionNodelet::recognizeServerCallback | ( | const cob_people_detection::RecognizeGoalConstPtr & | goal | ) |
Action server callback which manages the execution of the recognition functionality.
Definition at line 283 of file face_detection.cpp.
bool CobFaceDetectionNodelet::recognizeServiceServerCallback | ( | cob_people_detection::Recognition::Request & | req, |
cob_people_detection::Recognition::Response & | res | ||
) |
Definition at line 244 of file face_detection.cpp.
unsigned long CobFaceDetectionNodelet::saveAllData | ( | ) |
Definition at line 769 of file face_detection.cpp.
unsigned long CobFaceDetectionNodelet::saveRangeTrainImages | ( | cv::Mat & | xyz_image | ) |
Function to extract images for training range classifier
pc | ColoredPointCloud with images |
Definition at line 1069 of file face_detection.cpp.
unsigned long CobFaceDetectionNodelet::saveRecognizerData | ( | ) |
Definition at line 836 of file face_detection.cpp.
void CobFaceDetectionNodelet::saveServerCallback | ( | const cob_people_detection::SaveGoalConstPtr & | goal | ) |
Definition at line 479 of file face_detection.cpp.
unsigned long CobFaceDetectionNodelet::saveTrainingData | ( | ) |
Function to save the training data
Definition at line 790 of file face_detection.cpp.
unsigned long CobFaceDetectionNodelet::showAVGImage | ( | cv::Mat & | avgImage | ) |
Function to show the average image of all trained images
avgImage | The average image |
Definition at line 1055 of file face_detection.cpp.
void CobFaceDetectionNodelet::showServerCallback | ( | const cob_people_detection::ShowGoalConstPtr & | goal | ) |
Definition at line 507 of file face_detection.cpp.
void CobFaceDetectionNodelet::trainCaptureSampleServerCallback | ( | const cob_people_detection::TrainCaptureSampleGoalConstPtr & | goal | ) |
Definition at line 429 of file face_detection.cpp.
void CobFaceDetectionNodelet::trainContinuousCallback | ( | const sensor_msgs::PointCloud2::ConstPtr & | shared_image_msg, |
const sensor_msgs::Image::ConstPtr & | color_image_msg | ||
) |
Definition at line 1469 of file face_detection.cpp.
void CobFaceDetectionNodelet::trainContinuousServerCallback | ( | const cob_people_detection::TrainContinuousGoalConstPtr & | goal | ) |
Definition at line 324 of file face_detection.cpp.
boost::timed_mutex ipa_PeopleDetector::CobFaceDetectionNodelet::action_mutex_ [protected] |
secures write and read operations to varibales occupied_by_action_, etc.
Definition at line 206 of file face_detection.h.
cv::Mat ipa_PeopleDetector::CobFaceDetectionNodelet::avg_image_ [protected] |
Trained average Image.
Definition at line 174 of file face_detection.h.
bool ipa_PeopleDetector::CobFaceDetectionNodelet::capture_training_face_ [protected] |
can be set true by an action while in training mode. then an image is captured.
Definition at line 199 of file face_detection.h.
image_transport::SubscriberFilter ipa_PeopleDetector::CobFaceDetectionNodelet::color_camera_image_sub_ [protected] |
Color camera image topic.
Definition at line 148 of file face_detection.h.
std::vector<cv::Rect> ipa_PeopleDetector::CobFaceDetectionNodelet::color_faces_ [protected] |
Vector with detected faces.
Definition at line 182 of file face_detection.h.
ipa_SensorFusion::ColoredPointCloudPtr ipa_PeopleDetector::CobFaceDetectionNodelet::colored_pc_ [protected] |
Storage for acquired colored point cloud.
Definition at line 160 of file face_detection.h.
std::string ipa_PeopleDetector::CobFaceDetectionNodelet::current_training_id_ [protected] |
the ID of the current person who is trained
Definition at line 205 of file face_detection.h.
std::string ipa_PeopleDetector::CobFaceDetectionNodelet::directory_ [protected] |
directory for the data files
Definition at line 163 of file face_detection.h.
bool ipa_PeopleDetector::CobFaceDetectionNodelet::display_ [protected] |
enables debug output
Definition at line 203 of file face_detection.h.
bool ipa_PeopleDetector::CobFaceDetectionNodelet::do_recognition_ [protected] |
does people identification if true, else it's just people detection
Definition at line 202 of file face_detection.h.
cv::Mat ipa_PeopleDetector::CobFaceDetectionNodelet::eigen_val_mat_ [protected] |
Eigenvalues.
Definition at line 173 of file face_detection.h.
std::vector<cv::Mat> ipa_PeopleDetector::CobFaceDetectionNodelet::eigen_vectors_ [protected] |
Eigenvectors (spanning the face space)
Definition at line 172 of file face_detection.h.
cv::Mat ipa_PeopleDetector::CobFaceDetectionNodelet::face_class_avg_projections_ [protected] |
The average factors of the eigenvector decomposition from each face class.
Definition at line 176 of file face_detection.h.
image_transport::Publisher ipa_PeopleDetector::CobFaceDetectionNodelet::face_detection_image_pub_ [protected] |
topic for publishing the image containing the faces
Definition at line 149 of file face_detection.h.
std::vector<cv::Mat> ipa_PeopleDetector::CobFaceDetectionNodelet::face_images_ [protected] |
Trained face images.
Definition at line 167 of file face_detection.h.
publisher for the positions of the detected faces
Definition at line 152 of file face_detection.h.
const double ipa_PeopleDetector::CobFaceDetectionNodelet::FACE_SIZE_MAX_M = 0.35 [static, protected] |
Definition at line 210 of file face_detection.h.
double ipa_PeopleDetector::CobFaceDetectionNodelet::face_size_max_m_ [protected] |
in meters
Definition at line 215 of file face_detection.h.
const double ipa_PeopleDetector::CobFaceDetectionNodelet::FACE_SIZE_MIN_M = 0.12 [static, protected] |
Definition at line 209 of file face_detection.h.
double ipa_PeopleDetector::CobFaceDetectionNodelet::face_size_min_m_ [protected] |
in meters
Definition at line 214 of file face_detection.h.
int ipa_PeopleDetector::CobFaceDetectionNodelet::filename_ [protected] |
increasing number for files to save
Definition at line 165 of file face_detection.h.
fills the unassigned depth values in the depth image, must be true for a kinect sensor
Definition at line 217 of file face_detection.h.
std::vector<std::string> ipa_PeopleDetector::CobFaceDetectionNodelet::id_ [protected] |
Id of learned faces.
Definition at line 168 of file face_detection.h.
std::vector<std::string> ipa_PeopleDetector::CobFaceDetectionNodelet::id_unique_ [protected] |
A vector containing all different Ids from the training session exactly once (id_unique_[i] stores the corresponding id to the average face coordinates in the face subspace in face_class_avg_projections_.row(i))
Definition at line 169 of file face_detection.h.
Definition at line 147 of file face_detection.h.
Definition at line 193 of file face_detection.h.
const double ipa_PeopleDetector::CobFaceDetectionNodelet::MAX_FACE_Z_M = 8.0 [static, protected] |
Definition at line 211 of file face_detection.h.
double ipa_PeopleDetector::CobFaceDetectionNodelet::max_face_z_m_ [protected] |
in meters
Definition at line 216 of file face_detection.h.
int ipa_PeopleDetector::CobFaceDetectionNodelet::n_eigens_ [protected] |
Number of eigenvalues.
Definition at line 171 of file face_detection.h.
ROS node handle.
Definition at line 154 of file face_detection.h.
if the training is in continuous mode, this variable counts how many training images already have been collected for the current training job
Definition at line 200 of file face_detection.h.
bool ipa_PeopleDetector::CobFaceDetectionNodelet::occupied_by_action_ [protected] |
must be set true as long as an action callback is running or while the continuous recognition or training mode is running
Definition at line 196 of file face_detection.h.
People detector core code.
Definition at line 179 of file face_detection.h.
cv::SVM ipa_PeopleDetector::CobFaceDetectionNodelet::person_classifier_ [protected] |
classifier for the identity of a person
Definition at line 177 of file face_detection.h.
cv::Mat ipa_PeopleDetector::CobFaceDetectionNodelet::projected_train_face_mat_ [protected] |
Projected training faces (coefficients for the eigenvectors of the face subspace)
Definition at line 175 of file face_detection.h.
std::set<size_t> ipa_PeopleDetector::CobFaceDetectionNodelet::range_face_indices_with_color_face_detection_ [protected] |
this set stores which range faces also had a face detection in the color image
Definition at line 184 of file face_detection.h.
std::vector<cv::Rect> ipa_PeopleDetector::CobFaceDetectionNodelet::range_faces_ [protected] |
Vector with detected rangeFaces.
Definition at line 183 of file face_detection.h.
if true, the 3d face size is determined and only faces with reasonable size are accepted
Definition at line 218 of file face_detection.h.
Definition at line 192 of file face_detection.h.
is true while the recognition module is running
Definition at line 197 of file face_detection.h.
ros::ServiceServer ipa_PeopleDetector::CobFaceDetectionNodelet::recognize_service_server_ [protected] |
Service server to switch recognition on or off.
Definition at line 187 of file face_detection.h.
bool ipa_PeopleDetector::CobFaceDetectionNodelet::run_pca_ [protected] |
has to run a PCA when the data was modified
Definition at line 164 of file face_detection.h.
Definition at line 194 of file face_detection.h.
message_filters::Subscriber<sensor_msgs::PointCloud2> ipa_PeopleDetector::CobFaceDetectionNodelet::shared_image_sub_ [protected] |
Shared xyz image and color image topic.
Definition at line 146 of file face_detection.h.
Definition at line 195 of file face_detection.h.
message_filters::Synchronizer<message_filters::sync_policies::ApproximateTime<sensor_msgs::PointCloud2, sensor_msgs::Image> >* ipa_PeopleDetector::CobFaceDetectionNodelet::sync_pointcloud_ [protected] |
Definition at line 150 of file face_detection.h.
message_filters::Connection ipa_PeopleDetector::CobFaceDetectionNodelet::sync_pointcloud_callback_connection_ [protected] |
Definition at line 151 of file face_detection.h.
int ipa_PeopleDetector::CobFaceDetectionNodelet::threshold_ [protected] |
Threshold to detect unknown faces.
Definition at line 180 of file face_detection.h.
int ipa_PeopleDetector::CobFaceDetectionNodelet::threshold_fs_ [protected] |
Threshold to facespace.
Definition at line 181 of file face_detection.h.
TrainCaptureSampleServer* ipa_PeopleDetector::CobFaceDetectionNodelet::train_capture_sample_server_ [protected] |
Definition at line 191 of file face_detection.h.
TrainContinuousServer* ipa_PeopleDetector::CobFaceDetectionNodelet::train_continuous_server_ [protected] |
Definition at line 190 of file face_detection.h.
is true while the continuous training display is running
Definition at line 198 of file face_detection.h.