face_detection.cpp
Go to the documentation of this file.
00001 /****************************************************************
00002  *
00003  * Copyright (c) 2010
00004  *
00005  * Fraunhofer Institute for Manufacturing Engineering   
00006  * and Automation (IPA)
00007  *
00008  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
00009  *
00010  * Project name: care-o-bot
00011  * ROS stack name: cob_vision
00012  * ROS package name: cob_people_detection
00013  * Description:
00014  *                                                              
00015  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
00016  *                      
00017  * Author: Jan Fischer, email:jan.fischer@ipa.fhg.de
00018  * Author: Richard Bormann, email: richard.bormann@ipa.fhg.de
00019  * Supervised by: 
00020  *
00021  * Date of creation: 03/2011
00022  * ToDo:
00023  *
00024  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
00025  *
00026  * Redistribution and use in source and binary forms, with or without
00027  * modification, are permitted provided that the following conditions are met:
00028  *
00029  *     * Redistributions of source code must retain the above copyright
00030  *       notice, this list of conditions and the following disclaimer.
00031  *     * Redistributions in binary form must reproduce the above copyright
00032  *       notice, this list of conditions and the following disclaimer in the
00033  *       documentation and/or other materials provided with the distribution.
00034  *     * Neither the name of the Fraunhofer Institute for Manufacturing 
00035  *       Engineering and Automation (IPA) nor the names of its
00036  *       contributors may be used to endorse or promote products derived from
00037  *       this software without specific prior written permission.
00038  *
00039  * This program is free software: you can redistribute it and/or modify
00040  * it under the terms of the GNU Lesser General Public License LGPL as 
00041  * published by the Free Software Foundation, either version 3 of the 
00042  * License, or (at your option) any later version.
00043  * 
00044  * This program is distributed in the hope that it will be useful,
00045  * but WITHOUT ANY WARRANTY; without even the implied warranty of
00046  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00047  * GNU Lesser General Public License LGPL for more details.
00048  * 
00049  * You should have received a copy of the GNU Lesser General Public 
00050  * License LGPL along with this program. 
00051  * If not, see <http://www.gnu.org/licenses/>.
00052  *
00053  ****************************************************************/
00054 
00055 #include "cob_people_detection/face_detection.h"
00056 #include <pluginlib/class_list_macros.h>
00057 
00058 #ifdef __LINUX__
00059 #include "cob_vision_utils/GlobalDefines.h"
00060 #include "cob_vision_utils/VisionUtils.h"
00061 #else
00062 #include "cob_common/cob_vision_utils/common/include/cob_vision_utils/GlobalDefines.h"
00063 #include "cob_common/cob_vision_utils/common/include/cob_vision_utils/VisionUtils.h"
00064 #endif
00065 
00066 #include <opencv/highgui.h>
00067 
00068 PLUGINLIB_DECLARE_CLASS(ipa_PeopleDetector, CobFaceDetectionNodelet, ipa_PeopleDetector::CobFaceDetectionNodelet, nodelet::Nodelet)
00069 ;
00070 
00071 using namespace ipa_PeopleDetector;
00072 
00073 // Prevent deleting memory twice, when using smart pointer
00074 void voidDeleter(sensor_msgs::PointCloud2* const )
00075 {
00076 }
00077 
00078 //####################
00079 //#### node class ####
00080 CobFaceDetectionNodelet::CobFaceDetectionNodelet()
00081 {
00082         it_ = 0;
00083         sync_pointcloud_ = 0;
00084         people_detector_ = 0;
00085         train_continuous_server_ = 0;
00086         train_capture_sample_server_ = 0;
00087         recognize_server_ = 0;
00088         load_server_ = 0;
00089         save_server_ = 0;
00090         show_server_ = 0;
00091         occupied_by_action_ = false;
00092         recognize_server_running_ = false;
00093         train_continuous_server_running_ = false;
00094         number_training_images_captured_ = 0;
00095         do_recognition_ = true;
00096         display_ = false;
00097         directory_ = ros::package::getPath("cob_people_detection") + "/common/files/windows/"; // can be changed by a parameter
00098 }
00099 
00100 CobFaceDetectionNodelet::~CobFaceDetectionNodelet()
00101 {
00102         if (people_detector_ != 0)
00103                 delete people_detector_;
00104         if (train_continuous_server_ != 0)
00105                 delete train_continuous_server_;
00106         if (train_capture_sample_server_ != 0)
00107                 delete train_capture_sample_server_;
00108         if (recognize_server_ != 0)
00109                 delete recognize_server_;
00110         if (load_server_ != 0)
00111                 delete load_server_;
00112         if (save_server_ != 0)
00113                 delete save_server_;
00114         if (show_server_ != 0)
00115                 delete show_server_;
00116         if (it_ != 0)
00117                 delete it_;
00118         if (sync_pointcloud_ != 0)
00119                 delete sync_pointcloud_;
00120 }
00121 
00122 void CobFaceDetectionNodelet::onInit()
00123 {
00124         sync_pointcloud_ = new message_filters::Synchronizer<message_filters::sync_policies::ApproximateTime<sensor_msgs::PointCloud2, sensor_msgs::Image> >(2);
00125         node_handle_ = getNodeHandle();
00126         it_ = new image_transport::ImageTransport(node_handle_);
00127         face_position_publisher_ = node_handle_.advertise<cob_perception_msgs::DetectionArray>("face_position_array", 1);
00128         face_detection_image_pub_ = it_->advertise("face_detection_image", 1);
00129 
00130         recognize_server_ = new RecognizeServer(node_handle_, "recognize_server", boost::bind(&CobFaceDetectionNodelet::recognizeServerCallback, this, _1), false);
00131         recognize_server_->start();
00132 
00133         recognize_service_server_ = node_handle_.advertiseService("recognize_service_server", &CobFaceDetectionNodelet::recognizeServiceServerCallback, this);
00134 
00135         train_continuous_server_ = new TrainContinuousServer(node_handle_, "train_continuous_server", boost::bind(&CobFaceDetectionNodelet::trainContinuousServerCallback, this, _1),
00136                         false);
00137         train_continuous_server_->start();
00138 
00139         train_capture_sample_server_ = new TrainCaptureSampleServer(node_handle_, "train_capture_sample_server",
00140                         boost::bind(&CobFaceDetectionNodelet::trainCaptureSampleServerCallback, this, _1), false);
00141         train_capture_sample_server_->start();
00142 
00143         load_server_ = new LoadServer(node_handle_, "load_server", boost::bind(&CobFaceDetectionNodelet::loadServerCallback, this, _1), false);
00144         load_server_->start();
00145 
00146         save_server_ = new SaveServer(node_handle_, "save_server", boost::bind(&CobFaceDetectionNodelet::saveServerCallback, this, _1), false);
00147         save_server_->start();
00148 
00149         show_server_ = new ShowServer(node_handle_, "show_server", boost::bind(&CobFaceDetectionNodelet::showServerCallback, this, _1), false);
00150         show_server_->start();
00151 
00152         // Parameters
00153         std::cout << "\n--------------------------\nFace Detection Parameters:\n--------------------------\n";
00154         node_handle_.param("face_size_min_m", face_size_min_m_, FACE_SIZE_MIN_M);
00155         std::cout << "face_size_min_m = " << face_size_min_m_ << "\n";
00156         node_handle_.param("face_size_max_m", face_size_max_m_, FACE_SIZE_MAX_M);
00157         std::cout << "face_size_max_m = " << face_size_max_m_ << "\n";
00158         node_handle_.param("max_face_z_m", max_face_z_m_, MAX_FACE_Z_M);
00159         std::cout << "max_face_z_m = " << max_face_z_m_ << "\n";
00160         node_handle_.param("data_directory", directory_, directory_);
00161         std::cout << "data_directory = " << directory_ << "\n";
00162         node_handle_.param("fill_unassigned_depth_values", fill_unassigned_depth_values_, true);
00163         std::cout << "fill_unassigned_depth_values = " << fill_unassigned_depth_values_ << "\n";
00164         node_handle_.param("reason_about_3dface_size", reason_about_3dface_size_, true);
00165         std::cout << "reason_about_3dface_size = " << reason_about_3dface_size_ << "\n";
00166 
00167         // initializations
00168         init();
00169 
00170         //ros::spin(); not necessary with nodelets
00171 }
00172 
00173 unsigned long CobFaceDetectionNodelet::init()
00174 {
00175         std::cout << "CobFaceDetectionNodelet::init()..." << std::endl;
00176 
00177         shared_image_sub_.subscribe(node_handle_, "pointcloud", 1);
00178         color_camera_image_sub_.subscribe(*it_, "colorimage", 1);
00179         //      sync_pointcloud_->connectInput(shared_image_sub_, color_camera_image_sub_);
00180         //      sync_pointcloud_->registerCallback(boost::bind(&CobFaceDetectionNodelet::recognizeCallback, this, _1, _2));
00181 
00182         sync_pointcloud_->connectInput(shared_image_sub_, color_camera_image_sub_);
00183         sync_pointcloud_callback_connection_ = sync_pointcloud_->registerCallback(boost::bind(&CobFaceDetectionNodelet::recognizeCallback, this, _1, _2));
00184 
00185         std::cout << "   inputs connected." << std::endl;
00186 
00187 #ifdef __LINUX__
00188 #else
00189         colored_pc_ = ipa_SensorFusion::CreateColoredPointCloud();
00190 #endif
00191 
00192         if (people_detector_ != 0)
00193                 delete people_detector_;
00194         people_detector_ = new ipa_PeopleDetector::PeopleDetector();
00195 
00196         std::cout << "   PeopleDetector created." << std::endl;
00197 
00198         filename_ = 0;
00199 
00200         // load data for face recognition
00201         loadRecognizerData();
00202         std::cout << "   recognizer data loaded." << std::endl;
00203 
00204         // use this instead if the rdata.xml file is corrupted
00205         // todo:
00206         //      loadTrainingData(false);
00207         //      //loadRecognizerData();
00208         //      //loadTrainingData(false);
00209         //      run_pca_ = true;
00210         //      PCA();
00211         //      saveRecognizerData();
00212 
00213         std::string iniFileNameAndPath = directory_ + "peopleDetectorIni.xml";
00214 
00215         //if (CameraSensorsControlFlow::Init(directory, "peopleDetectorIni.xml", colorCamera0, colorCamera1, rangeImagingSensor) & ipa_Utils::RET_FAILED)
00216         //{
00217         //      std::cerr << "ERROR - CameraDataViewerControlFlow::Init:" << std::endl;
00218         //      std::cerr << "\t ... Could not initialize 'CameraSensorsControlFlow'" << std::endl;
00219         //      return ipa_Utils::RET_FAILED;
00220         //}
00221 
00222         if (people_detector_->Init(directory_) & ipa_Utils::RET_FAILED)
00223         {
00224                 std::cerr << "ERROR - PeopleDetector::Init:" << std::endl;
00225                 std::cerr << "\t ... Could not initialize people detector library.\n";
00226                 return ipa_Utils::RET_FAILED;
00227         }
00228         std::cout << "   PeopleDetector initilized." << std::endl;
00229 
00230         if (loadParameters(iniFileNameAndPath.c_str()) & ipa_Utils::RET_FAILED)
00231         {
00232                 std::cerr << "ERROR - PeopleDetector::Init:" << std::endl;
00233                 std::cerr << "\t ... Error while loading configuration file '" << std::endl;
00234                 std::cerr << "\t ... " << iniFileNameAndPath << "'.\n";
00235                 return ipa_Utils::RET_FAILED;
00236         }
00237         std::cout << "   ini-file loaded." << std::endl;
00238 
00239         run_pca_ = false;
00240 
00241         return ipa_Utils::RET_OK;
00242 }
00243 
00244 bool CobFaceDetectionNodelet::recognizeServiceServerCallback(cob_people_detection::Recognition::Request &req, cob_people_detection::Recognition::Response &res)
00245 {
00246         // secure this section with a mutex
00247         boost::timed_mutex::scoped_timed_lock lock(action_mutex_, boost::posix_time::milliseconds(2000));
00248 
00249         if (lock.owns_lock() == false || (occupied_by_action_ == true && recognize_server_running_ == false))
00250         {
00251                 // another action is running at the moment, first the other action has to finish or to be stopped before this action can run
00252                 std::cerr << "ERROR - PeopleDetector::recognizeServerCallback:" << std::endl;
00253                 std::cerr << "\t ... Another action is running at the moment. The other action has to finish or to be stopped before this action can run.\n";
00254                 res.success = ipa_Utils::RET_FAILED;
00255                 return false;
00256         }
00257 
00258         // read out req message
00259         // set up the recognition callback linkage
00260         if (req.running == true)
00261         {
00262                 // enable recognition
00263                 occupied_by_action_ = true;
00264                 recognize_server_running_ = true;
00265                 do_recognition_ = req.doRecognition;
00266                 display_ = req.display;
00267                 //cv::namedWindow("Face Detector");
00268                 //cv::waitKey(1);
00269                 //sync_pointcloud_->connectInput(shared_image_sub_, color_camera_image_sub_);
00270                 //sync_pointcloud_callback_connection_ = sync_pointcloud_->registerCallback(boost::bind(&CobFaceDetectionNodelet::recognizeCallback, this, _1, _2, req->doRecognition, req->display));
00271         }
00272         else
00273         {
00274                 // disable recognition
00275                 occupied_by_action_ = false;
00276                 recognize_server_running_ = false;
00277         }
00278 
00279         res.success = ipa_Utils::RET_OK;
00280         return true;
00281 }
00282 
00283 void CobFaceDetectionNodelet::recognizeServerCallback(const cob_people_detection::RecognizeGoalConstPtr& goal)
00284 {
00285         // secure this section with a mutex
00286         boost::timed_mutex::scoped_timed_lock lock(action_mutex_, boost::posix_time::milliseconds(2000));
00287 
00288         cob_people_detection::RecognizeResult result;
00289         if (lock.owns_lock() == false || (occupied_by_action_ == true && recognize_server_running_ == false))
00290         {
00291                 // another action is running at the moment, first the other action has to finish or to be stopped before this action can run
00292                 std::cerr << "ERROR - PeopleDetector::recognizeServerCallback:" << std::endl;
00293                 std::cerr << "\t ... Another action is running at the moment. The other action has to finish or to be stopped before this action can run.\n";
00294                 result.success = ipa_Utils::RET_FAILED;
00295                 recognize_server_->setSucceeded(result, "Some other action is handled at the moment.");
00296                 return;
00297         }
00298 
00299         // read out goal message
00300         // set up the recognition callback linkage
00301         if (goal->running == true)
00302         {
00303                 // enable recognition
00304                 occupied_by_action_ = true;
00305                 recognize_server_running_ = true;
00306                 do_recognition_ = goal->doRecognition;
00307                 display_ = goal->display;
00308                 //cv::namedWindow("Face Detector");
00309                 //cv::waitKey(1);
00310                 //sync_pointcloud_->connectInput(shared_image_sub_, color_camera_image_sub_);
00311                 //sync_pointcloud_callback_connection_ = sync_pointcloud_->registerCallback(boost::bind(&CobFaceDetectionNodelet::recognizeCallback, this, _1, _2, goal->doRecognition, goal->display));
00312         }
00313         else
00314         {
00315                 // disable recognition
00316                 occupied_by_action_ = false;
00317                 recognize_server_running_ = false;
00318         }
00319 
00320         result.success = ipa_Utils::RET_OK;
00321         recognize_server_->setSucceeded(result);
00322 }
00323 
00324 void CobFaceDetectionNodelet::trainContinuousServerCallback(const cob_people_detection::TrainContinuousGoalConstPtr& goal)
00325 {
00326         // secure this section with a mutex
00327         boost::timed_mutex::scoped_timed_lock lock(action_mutex_, boost::posix_time::milliseconds(2000));
00328 
00329         cob_people_detection::TrainContinuousResult result;
00330         if (lock.owns_lock() == false || (occupied_by_action_ == true && train_continuous_server_running_ == false))
00331         {
00332                 // another action is running at the moment, first the other action has to finish or to be stopped before this action can run
00333                 std::cerr << "ERROR - PeopleDetector::trainContinuousServerCallback:" << std::endl;
00334                 std::cerr << "\t ... Another action is running at the moment. The other action has to finish or to be stopped before this action can run.\n";
00335                 result.success = ipa_Utils::RET_FAILED;
00336                 train_continuous_server_->setSucceeded(result, "Some other action is handled at the moment.");
00337                 return;
00338         }
00339 
00340         // read out goal message
00341         // set up the recognition callback linkage
00342         if (goal->running == true)
00343         {
00344                 // enable training
00345                 capture_training_face_ = false;
00346                 current_training_id_ = goal->trainingID;
00347 
00348                 if (goal->appendData == true)
00349                         loadTrainingData(false);
00350                 else
00351                 {
00352                         filename_ = 0;
00353                         std::string path = directory_ + "TrainingData/";
00354                         try
00355                         {
00356                                 boost::filesystem::remove_all(path.c_str());
00357                                 boost::filesystem::create_directory(path.c_str());
00358                         } catch (const std::exception &ex)
00359                         {
00360                                 std::cerr << "ERROR - PeopleDetector::trainContinuousServerCallback():" << std::endl;
00361                                 std::cerr << "\t ... Exception catch of '" << ex.what() << "'" << std::endl;
00362                         }
00363                 }
00364                 occupied_by_action_ = true;
00365                 train_continuous_server_running_ = true;
00366                 //cv::namedWindow("Face Recognizer Training");
00367                 //cv::waitKey(10);
00368                 //sync_pointcloud_->connectInput(shared_image_sub_, color_camera_image_sub_);
00369                 //sync_pointcloud_callback_connection_ = sync_pointcloud_->registerCallback(boost::bind(&CobFaceDetectionNodelet::trainContinuousCallback, this, _1, _2));
00370                 std::cout << "train run...\n";
00371 
00372                 // check whether the continuous mode was enabled or if the image capture is manually triggered
00373                 if (goal->numberOfImagesToCapture > 0)
00374                 {
00375                         lock.unlock();
00376                         number_training_images_captured_ = 0;
00377                         bool capture = true;
00378                         while (capture)
00379                         {
00380                                 boost::timed_mutex::scoped_timed_lock lock(action_mutex_, boost::posix_time::milliseconds(10));
00381                                 if (lock.owns_lock() && capture_training_face_ == false)
00382                                         capture_training_face_ = true;
00383                                 capture = (number_training_images_captured_ < goal->numberOfImagesToCapture);
00384                         }
00385 
00386                         // turn off training mode
00387                         std::cout << "continuous train off...\n";
00388 
00389                         // disable training
00390                         occupied_by_action_ = false;
00391                         train_continuous_server_running_ = false;
00392 
00393                         // save images
00394                         saveTrainingData();
00395 
00396                         // do data analysis if enabled
00397                         if (goal->doPCA)
00398                         {
00399                                 PCA();
00400                                 saveRecognizerData();
00401                         }
00402                 }
00403         }
00404         else
00405         {
00406                 std::cout << "train off...\n";
00407                 // disable training
00408                 //sync_pointcloud_callback_connection_.disconnect();
00409                 occupied_by_action_ = false;
00410                 train_continuous_server_running_ = false;
00411                 //cv::destroyWindow("Face Recognizer Training");
00412                 //cv::waitKey(10);
00413 
00414                 // save images
00415                 saveTrainingData();
00416 
00417                 // do data analysis if enabled
00418                 if (goal->doPCA)
00419                 {
00420                         PCA();
00421                         saveRecognizerData();
00422                 }
00423         }
00424 
00425         result.success = ipa_Utils::RET_OK;
00426         train_continuous_server_->setSucceeded(result);
00427 }
00428 
00429 void CobFaceDetectionNodelet::trainCaptureSampleServerCallback(const cob_people_detection::TrainCaptureSampleGoalConstPtr& goal)
00430 {
00431         // secure this section with a mutex
00432         boost::timed_mutex::scoped_timed_lock lock(action_mutex_, boost::posix_time::milliseconds(10));
00433 
00434         cob_people_detection::TrainCaptureSampleResult result;
00435         if (lock.owns_lock() == false || (occupied_by_action_ == true && train_continuous_server_running_ == false) || occupied_by_action_ == false)
00436         {
00437                 // another action is running at the moment, first the other action has to finish or to be stopped before this action can run
00438                 std::cerr << "ERROR - PeopleDetector::trainCaptureSampleServerCallback:" << std::endl;
00439                 std::cerr
00440                                 << "\t ... Either the training mode is not started or another action is running at the moment. The other action has to finish or to be stopped before this action can run.\n";
00441                 result.success = ipa_Utils::RET_FAILED;
00442                 train_capture_sample_server_->setSucceeded(result, "Some other action is handled at the moment or training mode not started.");
00443                 return;
00444         }
00445 
00446         capture_training_face_ = true;
00447         result.success = ipa_Utils::RET_OK;
00448         train_capture_sample_server_->setSucceeded(result);
00449 }
00450 
00451 void CobFaceDetectionNodelet::loadServerCallback(const cob_people_detection::LoadGoalConstPtr& goal)
00452 {
00453         // secure this section with a mutex
00454         boost::timed_mutex::scoped_timed_lock lock(action_mutex_, boost::posix_time::milliseconds(2000));
00455 
00456         cob_people_detection::LoadResult result;
00457         if (lock.owns_lock() == false || occupied_by_action_ == true)
00458         {
00459                 // another action is running at the moment, first the other action has to finish or to be stopped before this action can run
00460                 std::cerr << "ERROR - PeopleDetector::loadServerCallback:" << std::endl;
00461                 std::cerr << "\t ... Another action is running at the moment. The other action has to finish or to be stopped before this action can run.\n";
00462                 result.success = ipa_Utils::RET_FAILED;
00463                 load_server_->setSucceeded(result, "Some other action is handled at the moment or training mode not started.");
00464                 return;
00465         }
00466 
00467         // load data
00468         result.success = ipa_Utils::RET_OK;
00469         if (goal->loadMode == 0)
00470                 result.success = loadAllData();
00471         else if (goal->loadMode == 1)
00472                 result.success = loadTrainingData(goal->doPCA);
00473         else if (goal->loadMode == 2)
00474                 result.success = loadRecognizerData();
00475 
00476         load_server_->setSucceeded(result);
00477 }
00478 
00479 void CobFaceDetectionNodelet::saveServerCallback(const cob_people_detection::SaveGoalConstPtr& goal)
00480 {
00481         // secure this section with a mutex
00482         boost::timed_mutex::scoped_timed_lock lock(action_mutex_, boost::posix_time::milliseconds(2000));
00483 
00484         cob_people_detection::SaveResult result;
00485         if (lock.owns_lock() == false || occupied_by_action_ == true)
00486         {
00487                 // another action is running at the moment, first the other action has to finish or to be stopped before this action can run
00488                 std::cerr << "ERROR - PeopleDetector::saveServerCallback:" << std::endl;
00489                 std::cerr << "\t ... Another action is running at the moment. The other action has to finish or to be stopped before this action can run.\n";
00490                 result.success = ipa_Utils::RET_FAILED;
00491                 save_server_->setSucceeded(result, "Some other action is handled at the moment or training mode not started.");
00492                 return;
00493         }
00494 
00495         // save data
00496         result.success = ipa_Utils::RET_OK;
00497         if (goal->saveMode == 0)
00498                 result.success = saveAllData();
00499         else if (goal->saveMode == 1)
00500                 result.success = saveTrainingData();
00501         else if (goal->saveMode == 2)
00502                 result.success = saveRecognizerData();
00503 
00504         save_server_->setSucceeded(result);
00505 }
00506 
00507 void CobFaceDetectionNodelet::showServerCallback(const cob_people_detection::ShowGoalConstPtr& goal)
00508 {
00509         // secure this section with a mutex
00510         boost::timed_mutex::scoped_timed_lock lock(action_mutex_, boost::posix_time::milliseconds(2000));
00511 
00512         cob_people_detection::ShowResult result;
00513         if (lock.owns_lock() == false || occupied_by_action_ == true)
00514         {
00515                 // another action is running at the moment, first the other action has to finish or to be stopped before this action can run
00516                 std::cerr << "ERROR - PeopleDetector::showServerCallback:" << std::endl;
00517                 std::cerr << "\t ... Another action is running at the moment. The other action has to finish or to be stopped before this action can run.\n";
00518                 result.success = ipa_Utils::RET_FAILED;
00519                 show_server_->setSucceeded(result, "Some other action is handled at the moment or training mode not started.");
00520                 return;
00521         }
00522 
00523         // display
00524         loadTrainingData(false);
00525         if (goal->mode == 0)
00526         {
00527                 // show average image
00528                 cv::Mat avgImage(100, 100, CV_8UC1);
00529                 PCA();
00530                 showAVGImage(avgImage);
00531 
00532                 cv::namedWindow("AVGImage");
00533                 cv::imshow("AVGImage", avgImage);
00534                 cv::waitKey(3000);
00535 
00536                 cv::destroyWindow("AVGImage");
00537         }
00538         else if (goal->mode == 1)
00539         {
00540                 // show eigenfaces
00541                 cv::Mat eigenface;
00542                 cv::namedWindow("Eigenfaces");
00543                 PCA();
00544                 for (int i = 0; i < (int)20/*face_images_.size()-1*/; i++)
00545                 {
00546                         getEigenface(eigenface, i);
00547                         cv::imshow("Eigenfaces", eigenface);
00548                         cv::waitKey();
00549                 }
00550                 cv::destroyWindow("Eigenfaces");
00551         }
00552 
00553         result.success = ipa_Utils::RET_OK;
00554         show_server_->setSucceeded(result);
00555 }
00556 
00557 unsigned long CobFaceDetectionNodelet::detectFaces(cv::Mat& xyz_image, cv::Mat& color_image)
00558 {
00559         cv::Mat xyz_image_8U3;
00560         ipa_Utils::ConvertToShowImage(xyz_image, xyz_image_8U3, 3);
00561         if (people_detector_->DetectFaces(color_image, xyz_image_8U3, color_faces_, range_faces_, range_face_indices_with_color_face_detection_, fill_unassigned_depth_values_)
00562                         & ipa_Utils::RET_FAILED)
00563         {
00564                 std::cerr << "ERROR - PeopleDetection::detectFaces" << std::endl;
00565                 std::cerr << "\t ... Could not detect faces.\n";
00566                 return ipa_Utils::RET_FAILED;
00567         }
00568 
00569         // check whether the color faces have a reasonable 3D size
00570         std::vector < cv::Rect > tempFaces = color_faces_; // todo: why copy to tempFaces?
00571         color_faces_.clear();
00572         // For each face...
00573         for (uint iface = 0; iface < tempFaces.size(); iface++)
00574         {
00575                 cv::Rect& face = tempFaces[iface];
00576 
00577                 //              one_face.box2d = faces_vec[iface];
00578                 //              one_face.id = i; // The cascade that computed this face.
00579 
00580                 // Get the median disparity in the middle half of the bounding box.
00581                 int uStart = floor(0.25 * face.width);
00582                 int uEnd = floor(0.75 * face.width) + 1;
00583                 int vStart = floor(0.25 * face.height);
00584                 int vEnd = floor(0.75 * face.height) + 1;
00585                 int du = abs(uEnd - uStart);
00586 
00587                 cv::Mat faceRegion = xyz_image(face);
00588                 cv::Mat tmat(1, du * abs(vEnd - vStart), CV_32FC1); // vector of all depth values in the face region
00589                 float* tmatPtr = (float*)tmat.data;
00590                 for (int v = vStart; v < vEnd; v++)
00591                 {
00592                         float* zPtr = (float*)faceRegion.row(v).data;
00593                         zPtr += 2 + 3 * uStart;
00594                         for (int u = uStart; u < uEnd; u++)
00595                         {
00596                                 float depthval = *zPtr;
00597                                 if (!isnan(depthval))
00598                                         *tmatPtr = depthval;
00599                                 else
00600                                         *tmatPtr = 1e20;
00601                                 tmatPtr++;
00602                                 zPtr += 3;
00603                         }
00604                 }
00605                 //
00606                 //
00607                 //              int vector_position = 0;
00608                 //              for (int v=vStart; v<vEnd; v++)
00609                 //                for (int u=uStart; u<uEnd; u++, vector_position++)
00610                 //                {
00611                 //                      float depthval = xyz_image.at<cv::Vec3f>(v,u).z;
00612                 //                      if (!isnan(depthval)) tmat.at<float>(0,vector_position) = depthval;
00613                 //                      else tmat.at<float>(0,vector_position) = 1e20;
00614                 //                }
00615 
00616                 cv::Mat tmat_sorted;
00617                 cv::sort(tmat, tmat_sorted, CV_SORT_EVERY_COLUMN + CV_SORT_DESCENDING);
00618                 double avg_depth = tmat_sorted.at<float>(floor(cv::countNonZero(tmat_sorted >= 0.0) * 0.5)); // Get the middle valid disparity (-1 disparities are invalid)
00619 
00620                 // Fill in the rest of the face data structure.
00621                 //              one_face.center2d = cv::Point2d(one_face.box2d.x+one_face.box2d.width*0.5,
00622                 //                                                                              one_face.box2d.y+one_face.box2d.height*0.5);
00623                 //              one_face.radius2d = one_face.box2d.width*0.5;
00624 
00625                 // If the median disparity was valid and the face is a reasonable size, the face status is "good".
00626                 // If the median disparity was valid but the face isn't a reasonable size, the face status is "bad".
00627                 // Otherwise, the face status is "unknown".
00628                 // Only bad faces are removed
00629                 if (avg_depth > 0)
00630                 {
00631                         double radiusX, radiusY, radius3d = 1e20;
00632                         cv::Vec3f a, b;
00633                         // vertical line regularly lies completely on the head whereas this does not hold very often for the horizontal line crossing the bounding box of the face
00634                         // rectangle in the middle
00635                         a = xyz_image.at<cv::Vec3f>((int)(face.y + face.height * 0.25), (int)(face.x + 0.5 * face.width));
00636                         b = xyz_image.at<cv::Vec3f>((int)(face.y + face.height * 0.75), (int)(face.x + 0.5 * face.width));
00637                         if (display_)
00638                                 std::cout << "a: " << a.val[0] << " " << a.val[1] << " " << a.val[2] << "   b: " << " " << b.val[0] << " " << b.val[1] << " " << b.val[2] << "\n";
00639                         if (isnan(a.val[0]) || isnan(b.val[0]))
00640                                 radiusY = 0.0;
00641                         else
00642                                 radiusY = cv::norm(b - a);
00643                         radius3d = radiusY;
00644 
00645                         // for radius estimation with the horizontal line through the face rectangle use points which typically still lie on the face and not in the background
00646                         a = xyz_image.at<cv::Vec3f>((int)(face.y + face.height * 0.5), (int)(face.x + face.width * 0.25));
00647                         b = xyz_image.at<cv::Vec3f>((int)(face.y + face.height * 0.5), (int)(face.x + face.width * 0.75));
00648                         if (display_)
00649                                 std::cout << "a: " << a.val[0] << " " << a.val[1] << " " << a.val[2] << "   b: " << " " << b.val[0] << " " << b.val[1] << " " << b.val[2] << "\n";
00650                         if (isnan(a.val[0]) || isnan(b.val[0]))
00651                                 radiusX = 0.0;
00652                         else
00653                         {
00654                                 radiusX = cv::norm(b - a);
00655                                 if (radiusY != 0.0)
00656                                         radius3d = (radiusX + radiusY) * 0.5;
00657                                 else
00658                                         radius3d = radiusX;
00659                         }
00660 
00661                         //                      cv::Point pup(face.x+0.5*face.width, face.y+face.height*0.25);
00662                         //                      cv::Point plo(face.x+0.5*face.width, face.y+face.height*0.75);
00663                         //                      cv::Point ple(face.x+face.width*0.25, face.y+face.height*0.5);
00664                         //                      cv::Point pri(face.x+face.width*0.75, face.y+face.height*0.5);
00665                         //                      cv::line(xyz_image_8U3, pup, plo, CV_RGB(255, 255, 255), 2);
00666                         //                      cv::line(xyz_image_8U3, ple, pri, CV_RGB(255, 255, 255), 2);
00667 
00668                         if (display_)
00669                         {
00670                                 std::cout << "radiusX: " << radiusX << "  radiusY: " << radiusY << "\n";
00671                                 std::cout << "avg_depth: " << avg_depth << " > max_face_z_m_: " << max_face_z_m_ << " ?  2*radius3d: " << 2.0 * radius3d << " < face_size_min_m_: "
00672                                                 << face_size_min_m_ << " ?  2radius3d: " << 2.0 * radius3d << " > face_size_max_m_:" << face_size_max_m_ << "?\n";
00673                         }
00674                         if (reason_about_3dface_size_ == true && radius3d > 0.0 && (avg_depth > max_face_z_m_ || 2.0 * radius3d < face_size_min_m_ || 2.0 * radius3d > face_size_max_m_))
00675                                 continue; // face does not match normal human appearance
00676                 }
00677                 color_faces_.push_back(face);
00678         }
00679         //                      imshow("xyz image", xyz_image_8U3);
00680         //                      cv::waitKey(10);
00681 
00682         return ipa_Utils::RET_OK;
00683 }
00684 
00685 unsigned long CobFaceDetectionNodelet::recognizeFace(cv::Mat& color_image, std::vector<int>& index)
00686 {
00687         if (people_detector_->RecognizeFace(color_image, color_faces_, &n_eigens_, eigen_vectors_, avg_image_, face_class_avg_projections_, index, &threshold_, &threshold_fs_,
00688                         eigen_val_mat_, /*&person_classifier_*/0) & ipa_Utils::RET_FAILED)
00689         {
00690                 std::cerr << "ERROR - PeopleDetector::recognizeFace:" << std::endl;
00691                 std::cerr << "\t ... Error while recognizing faces.\n";
00692                 return ipa_Utils::RET_FAILED;
00693         }
00694 
00695         return ipa_Utils::RET_OK;
00696 }
00697 
00698 unsigned long CobFaceDetectionNodelet::addFace(cv::Mat& image, std::string id)
00699 {
00700         // addFace should only be called if there is exactly one face found --> so we access it with color_faces_[0]
00701         if (people_detector_->AddFace(image, color_faces_[0], id, face_images_, id_) & ipa_Utils::RET_FAILED)
00702         {
00703                 std::cerr << "ERROR - PeopleDetectorControlFlow::AddFace:" << std::endl;
00704                 std::cerr << "\t ... Could not save face.\n";
00705                 return ipa_Utils::RET_FAILED;
00706         }
00707         run_pca_ = true;
00708 
00709         return ipa_Utils::RET_OK;
00710 }
00711 
00712 unsigned long CobFaceDetectionNodelet::PCA()
00713 {
00714         // only run PCA if new data has arrived after last computation
00715         if (!run_pca_)
00716         {
00717                 //std::cout << "INFO - PeopleDetector::PCA:" << std::endl;
00718                 //std::cout << "\t ... PCA algorithm skipped.\n";
00719                 return ipa_Utils::RET_OK;
00720         }
00721 
00722         if (face_images_.size() < 2)
00723         {
00724                 std::cout << "WARNING - PeopleDetector::ConsoleGUI:" << std::endl;
00725                 std::cout << "\t ... Less than two images are trained.\n";
00726                 return ipa_Utils::RET_OK;
00727         }
00728 
00729         // Delete memory
00730         eigen_vectors_.clear();
00731 
00732         // mirror images
00733         //todo:
00734         //      std::vector<cv::Mat> face_images_doubled;
00735         //      std::vector<std::string> id_doubled;
00736         //      for (int i=0; i<(int)face_images_.size(); i++)
00737         //      {
00738         //              face_images_doubled.push_back(face_images_[i]);
00739         //              id_doubled.push_back(id_[i]);
00740         //              cv::Mat temp;
00741         //              cv::flip(face_images_[i], temp, 1);
00742         //              face_images_doubled.push_back(temp);
00743         //              id_doubled.push_back(id_[i]);
00744         //      }
00745 
00746         // Do PCA
00747         if (people_detector_->PCA(&n_eigens_, eigen_vectors_, eigen_val_mat_, avg_image_, face_images_/*doubled*/, projected_train_face_mat_) & ipa_Utils::RET_FAILED)
00748         {
00749                 std::cerr << "ERROR - PeopleDetectorControlFlow::PCA:" << std::endl;
00750                 std::cerr << "\t ... Error while PCA.\n";
00751                 return ipa_Utils::RET_FAILED;
00752         }
00753 
00754         // Calculate FaceClasses
00755         std::cout << "Debug: n_eigens: " << n_eigens_ << " id: " << id_.size() << "\n";
00756         if (people_detector_->CalculateFaceClasses(projected_train_face_mat_, id_/*doubled*/, &n_eigens_, face_class_avg_projections_, id_unique_, /*&person_classifier_*/0)
00757                         & ipa_Utils::RET_FAILED)
00758         {
00759                 std::cerr << "ERROR - PeopleDetectorControlFlow::PCA:" << std::endl;
00760                 std::cerr << "\t ... Error while calculating FaceClasses.\n";
00761                 return ipa_Utils::RET_FAILED;
00762         }
00763 
00764         run_pca_ = false;
00765 
00766         return ipa_Utils::RET_OK;
00767 }
00768 
00769 unsigned long CobFaceDetectionNodelet::saveAllData()
00770 {
00771         //      try
00772         //      {
00773         //              fs::remove_all(path.c_str());
00774         //              fs::create_directory(path.c_str());
00775         //      }
00776         //      catch (const std::exception &ex)
00777         //      {
00778         //              std::cerr << "ERROR - PeopleDetector::SaveTrainingData():" << std::endl;
00779         //              std::cerr << "\t ... Exception catch of '" << ex.what() << "'" << std::endl;
00780         //      }
00781 
00782         if (saveTrainingData() != ipa_Utils::RET_OK)
00783                 return ipa_Utils::RET_FAILED;
00784         if (saveRecognizerData() != ipa_Utils::RET_OK)
00785                 return ipa_Utils::RET_FAILED;
00786 
00787         return ipa_Utils::RET_OK;
00788 }
00789 
00790 unsigned long CobFaceDetectionNodelet::saveTrainingData()
00791 {
00792         std::string path = directory_ + "TrainingData/";
00793         std::string filename = "tdata.xml";
00794         std::string img_ext = ".bmp";
00795 
00796         std::ostringstream complete;
00797         complete << path << filename;
00798 
00799         cv::FileStorage fileStorage(complete.str().c_str(), cv::FileStorage::WRITE);
00800         if (!fileStorage.isOpened())
00801         {
00802                 std::cout << "WARNING - PeopleDetector::SaveTrainingData:" << std::endl;
00803                 std::cout << "\t ... Can't save training data.\n";
00804                 return ipa_Utils::RET_OK;
00805         }
00806 
00807         // Ids
00808         fileStorage << "id_num" << (int)id_.size();
00809         for (int i = 0; i < (int)id_.size(); i++)
00810         {
00811                 std::ostringstream tag;
00812                 tag << "id_" << i;
00813                 fileStorage << tag.str().c_str() << id_[i].c_str();
00814         }
00815 
00816         // Face images
00817         fileStorage << "faces_num" << (int)face_images_.size();
00818         for (int i = 0; i < (int)face_images_.size(); i++)
00819         {
00820                 std::ostringstream img, shortname;
00821                 img << path << i << img_ext;
00822                 shortname << "TrainingData/" << i << img_ext;
00823                 std::ostringstream tag;
00824                 tag << "img_" << i;
00825                 fileStorage << tag.str().c_str() << shortname.str().c_str();
00826                 cv::imwrite(img.str().c_str(), face_images_[i]);
00827         }
00828 
00829         fileStorage.release();
00830 
00831         std::cout << "INFO - PeopleDetector::SaveTrainingData:" << std::endl;
00832         std::cout << "\t ... " << face_images_.size() << " images saved.\n";
00833         return ipa_Utils::RET_OK;
00834 }
00835 
00836 unsigned long CobFaceDetectionNodelet::saveRecognizerData()
00837 {
00838         std::string path = directory_ + "TrainingData/";
00839         std::string filename = "rdata.xml";
00840 
00841         std::ostringstream complete;
00842         complete << path << filename;
00843 
00844         cv::FileStorage fileStorage(complete.str().c_str(), cv::FileStorage::WRITE);
00845         if (!fileStorage.isOpened())
00846         {
00847                 std::cout << "WARNING - PeopleDetector::saveRecognizerData:" << std::endl;
00848                 std::cout << "\t ... Can't save training data.\n";
00849                 return ipa_Utils::RET_OK;
00850         }
00851 
00852         // Number eigenvalues/eigenvectors
00853         fileStorage << "eigens_num" << n_eigens_;
00854 
00855         // Eigenvectors
00856         for (int i = 0; i < n_eigens_; i++)
00857         {
00858                 std::ostringstream tag;
00859                 tag << "ev_" << i;
00860                 fileStorage << tag.str().c_str() << eigen_vectors_[i];
00861         }
00862 
00863         // Eigenvalue matrix
00864         fileStorage << "eigen_val_mat" << eigen_val_mat_;
00865 
00866         // Average image
00867         fileStorage << "avg_image" << avg_image_;
00868 
00869         // Projection coefficients of the training faces
00870         fileStorage << "projected_train_face_mat" << projected_train_face_mat_;
00871 
00872         // Unique Ids (id_unique_[i] stores the corresponding id to the average face coordinates in the face subspace in face_class_avg_projections_.row(i))
00873         fileStorage << "id_unique_num" << (int)id_unique_.size();
00874         for (int i = 0; i < (int)id_unique_.size(); i++)
00875         {
00876                 std::ostringstream tag;
00877                 tag << "id_unique_" << i;
00878                 fileStorage << tag.str().c_str() << id_unique_[i].c_str();
00879         }
00880 
00881         // The average factors of the eigenvector decomposition from each face class
00882         fileStorage << "face_class_avg_projections" << face_class_avg_projections_;
00883 
00884         fileStorage.release();
00885 
00886         // save classifier
00887         std::string classifierFile = path + "svm.dat";
00888         //person_classifier_.save(classifierFile.c_str());
00889 
00890         std::cout << "INFO - PeopleDetector::saveRecognizerData:" << std::endl;
00891         std::cout << "\t ... recognizer data saved.\n";
00892         return ipa_Utils::RET_OK;
00893 }
00894 
00895 unsigned long CobFaceDetectionNodelet::loadAllData()
00896 {
00897         if (loadTrainingData(true) != ipa_Utils::RET_OK)
00898                 return ipa_Utils::RET_FAILED;
00899         if (loadRecognizerData() != ipa_Utils::RET_OK)
00900                 return ipa_Utils::RET_FAILED;
00901 
00902         return ipa_Utils::RET_OK;
00903 }
00904 
00905 unsigned long CobFaceDetectionNodelet::loadTrainingData(bool runPCA)
00906 {
00907         std::string path = directory_ + "TrainingData/";
00908         std::string filename = "tdata.xml";
00909 
00910         std::ostringstream complete;
00911         complete << path << filename;
00912 
00913         if (fs::is_directory(path.c_str()))
00914         {
00915                 cv::FileStorage fileStorage(complete.str().c_str(), cv::FileStorage::READ);
00916                 if (!fileStorage.isOpened())
00917                 {
00918                         std::cout << "WARNING - PeopleDetector::loadTrainingData:" << std::endl;
00919                         std::cout << "\t ... Cant open " << complete.str() << ".\n";
00920                         return ipa_Utils::RET_OK;
00921                 }
00922 
00923                 // Ids
00924                 id_.clear();
00925                 int id_num = (int)fileStorage["id_num"];
00926                 for (int i = 0; i < id_num; i++)
00927                 {
00928                         std::ostringstream tag;
00929                         tag << "id_" << i;
00930                         id_.push_back((std::string)fileStorage[tag.str().c_str()]);
00931                 }
00932 
00933                 // Images
00934                 face_images_.clear();
00935                 int faces_num = (int)fileStorage["faces_num"];
00936                 for (int i = 0; i < faces_num; i++)
00937                 {
00938                         std::ostringstream tag;
00939                         tag << "img_" << i;
00940                         std::string path = directory_ + (std::string)fileStorage[tag.str().c_str()];
00941                         cv::Mat temp = cv::imread(path.c_str(), 0);
00942                         face_images_.push_back(temp);
00943                 }
00944 
00945                 // set next free filename
00946                 filename_ = faces_num;
00947 
00948                 fileStorage.release();
00949 
00950                 // Run PCA - now or later
00951                 run_pca_ = true;
00952                 if (runPCA)
00953                         PCA();
00954 
00955                 std::cout << "INFO - PeopleDetector::loadTrainingData:" << std::endl;
00956                 std::cout << "\t ... " << faces_num << " images loaded.\n";
00957         }
00958         else
00959         {
00960                 std::cerr << "ERROR - PeopleDetector::loadTrainingData:" << std::endl;
00961                 std::cerr << "\t .... Path '" << path << "' is not a directory." << std::endl;
00962                 return ipa_Utils::RET_FAILED;
00963         }
00964 
00965         return ipa_Utils::RET_OK;
00966 }
00967 
00968 unsigned long CobFaceDetectionNodelet::loadRecognizerData()
00969 {
00970         std::string path = directory_ + "TrainingData/";
00971         std::string filename = "rdata.xml";
00972 
00973         std::ostringstream complete;
00974         complete << path << filename;
00975 
00976         if (fs::is_directory(path.c_str()))
00977         {
00978                 cv::FileStorage fileStorage(complete.str().c_str(), cv::FileStorage::READ);
00979                 if (!fileStorage.isOpened())
00980                 {
00981                         std::cout << "WARNING - PeopleDetector::loadRecognizerData:" << std::endl;
00982                         std::cout << "\t ... Cant open " << complete.str() << ".\n";
00983                         return ipa_Utils::RET_OK;
00984                 }
00985                 std::cout << "   loading recognizer data..." << std::endl;
00986 
00987                 // Number eigenvalues/eigenvectors
00988                 n_eigens_ = (int)fileStorage["eigens_num"];
00989 
00990                 // Eigenvectors
00991                 eigen_vectors_.clear();
00992                 eigen_vectors_.resize(n_eigens_, cv::Mat());
00993                 for (int i = 0; i < n_eigens_; i++)
00994                 {
00995                         std::ostringstream tag;
00996                         tag << "ev_" << i;
00997                         fileStorage[tag.str().c_str()] >> eigen_vectors_[i];
00998                 }
00999 
01000                 // Eigenvalue matrix
01001                 eigen_val_mat_ = cv::Mat();
01002                 fileStorage["eigen_val_mat"] >> eigen_val_mat_;
01003 
01004                 // Average image
01005                 avg_image_ = cv::Mat();
01006                 fileStorage["avg_image"] >> avg_image_;
01007 
01008                 // Projections of the training faces
01009                 projected_train_face_mat_ = cv::Mat();
01010                 fileStorage["projected_train_face_mat"] >> projected_train_face_mat_;
01011 
01012                 // Unique Ids (id_unique_[i] stores the corresponding id to the average face coordinates in the face subspace in face_class_avg_projections_.row(i))
01013                 id_unique_.clear();
01014                 int idUniqueNum = (int)fileStorage["id_unique_num"];
01015                 for (int i = 0; i < idUniqueNum; i++)
01016                 {
01017                         std::ostringstream tag;
01018                         tag << "id_unique_" << i;
01019                         id_unique_.push_back((std::string)fileStorage[tag.str().c_str()]);
01020                 }
01021 
01022                 // The average factors of the eigenvector decomposition from each face class
01023                 face_class_avg_projections_ = cv::Mat();
01024                 fileStorage["face_class_avg_projections"] >> face_class_avg_projections_;
01025 
01026                 fileStorage.release();
01027 
01028                 // load classifier
01029                 std::string classifierFile = path + "svm.dat";
01030                 //person_classifier_.load(classifierFile.c_str());
01031 
01032                 // do not run PCA
01033                 run_pca_ = false;
01034 
01035                 std::cout << "INFO - PeopleDetector::loadRecognizerData:" << std::endl;
01036                 std::cout << "\t ... recognizer data loaded.\n";
01037         }
01038         else
01039         {
01040                 std::cerr << "ERROR - PeopleDetector::loadRecognizerData():" << std::endl;
01041                 std::cerr << "\t .... Path '" << path << "' is not a directory." << std::endl;
01042                 return ipa_Utils::RET_FAILED;
01043         }
01044 
01045         return ipa_Utils::RET_OK;
01046 }
01047 
01048 unsigned long CobFaceDetectionNodelet::getEigenface(cv::Mat& eigenface, int index)
01049 {
01050         cv::normalize(eigen_vectors_[index], eigenface, 0, 255, cv::NORM_MINMAX, CV_8UC1);
01051 
01052         return ipa_Utils::RET_OK;
01053 }
01054 
01055 unsigned long CobFaceDetectionNodelet::showAVGImage(cv::Mat& avgImage)
01056 {
01057         if (!run_pca_ && face_images_.size() < 2)
01058         {
01059                 std::cerr << "PeopleDetector::showAvgImage()" << std::endl;
01060                 std::cerr << "No AVG image calculated" << std::endl;
01061                 return 0;
01062         }
01063 
01064         cv::normalize(avg_image_, avgImage, 0, 255, cv::NORM_MINMAX, CV_8UC1);
01065 
01066         return ipa_Utils::RET_OK;
01067 }
01068 
01069 unsigned long CobFaceDetectionNodelet::saveRangeTrainImages(cv::Mat& xyz_image)
01070 {
01071         std::string path = directory_ + "haarcascades/";
01072         std::string img_ext = ".jpg";
01073         cv::Mat xyzImage_8U3(xyz_image.size(), CV_8UC3); //IplImage* xyzImage_8U3 = cvCreateImage(cvGetSize(pc->GetXYZImage()), 8, 3);
01074         ipa_Utils::ConvertToShowImage(xyz_image, xyzImage_8U3, 3);
01075 
01076         for (int i = 0; i < (int)color_faces_.size(); i++)
01077         {
01078                 cv::Mat xyzImage_8U3_resized(100, 100, CV_8UC3); //cvCreateImage(cvSize(100,100), 8, 3); 8=IPL_DEPTH_8U
01079 
01080                 double scale = 1.6;
01081                 cv::Rect rangeFace;
01082                 rangeFace.height = (int)(color_faces_[i].height * scale);
01083                 rangeFace.width = (int)(color_faces_[i].width * scale);
01084                 rangeFace.x = color_faces_[i].x - ((rangeFace.width - color_faces_[i].width) / 2);
01085                 rangeFace.y = color_faces_[i].y - ((rangeFace.height - color_faces_[i].height) / 2) - 10;
01086 
01087                 cv::Mat xyzImage_8U3_roi = xyzImage_8U3(rangeFace);
01088                 //cvSetImageROI(xyzImage_8U3, rangeFace);
01089                 cv::resize(xyzImage_8U3_roi, xyzImage_8U3_resized, xyzImage_8U3_resized.size());
01090 
01091                 std::ostringstream file;
01092                 file << path << filename_ << img_ext;
01093 
01094                 cv::imwrite(file.str().c_str(), xyzImage_8U3_resized);//cvSaveImage(file.str().c_str(), xyzImage_8U3_resized);
01095                 filename_++;
01096         }
01097 
01098         return ipa_Utils::RET_OK;
01099 }
01100 
01101 //unsigned long CobFaceDetectionNodelet::getMeasurement(const sensor_msgs::PointCloud2::ConstPtr& shared_image_msg, const sensor_msgs::Image::ConstPtr& color_image_msg)
01102 //{
01103 //      cv::Mat color_image_8U3(shared_image_msg->height, shared_image_msg->width, CV_8UC3);
01104 //      cv::Mat xyz_image_32F3(shared_image_msg->height, shared_image_msg->width, CV_32FC3);
01105 //      float* f_ptr = 0;
01106 //      const uint8_t* data_ptr = 0;
01107 //      unsigned char* uc_ptr = 0;
01108 //      unsigned int xyz_offset = shared_image_msg->fields[0].offset;
01109 //      unsigned int rgb_offset = shared_image_msg->fields[3].offset;
01110 //      size_t b_offset = 2*sizeof(unsigned char);
01111 //      size_t g_offset = sizeof(unsigned char);
01112 //      size_t r_offset = 0;
01113 //      unsigned int col_times_3 = 0;
01114 //      for (unsigned int row = 0; row < shared_image_msg->height; row++)
01115 //      {
01116 //              uc_ptr = color_image_8U3.ptr<unsigned char>(row);
01117 //              f_ptr = xyz_image_32F3.ptr<float>(row);
01118 //
01119 //              data_ptr = &shared_image_msg->data[row * shared_image_msg->width * shared_image_msg->point_step];
01120 //
01121 //              for (unsigned int col = 0; col < shared_image_msg->width; col++)
01122 //              {
01123 //                      col_times_3 = 3*col;
01124 //                      // Reorder incoming image channels
01125 //                      memcpy(&uc_ptr[col_times_3], &data_ptr[col * shared_image_msg->point_step + rgb_offset + b_offset], sizeof(unsigned char));
01126 //                      memcpy(&uc_ptr[col_times_3 + 1], &data_ptr[col * shared_image_msg->point_step + rgb_offset + g_offset], sizeof(unsigned char));
01127 //                      memcpy(&uc_ptr[col_times_3 + 2], &data_ptr[col * shared_image_msg->point_step + rgb_offset + r_offset], sizeof(unsigned char));
01128 //
01129 //                      memcpy(&f_ptr[col_times_3], &data_ptr[col * shared_image_msg->point_step + xyz_offset], 3*sizeof(float));
01130 //              }
01131 //      }
01132 //
01133 //#ifdef __LINUX__
01134 //      color_image_ = color_image_8U3;
01135 //      range_image_ = xyz_image_32F3;
01136 //#else
01137 //      // Images are cloned within setter functions
01138 //      colored_pc_->SetColorImage(color_image_8U3);
01139 //      colored_pc_->SetXYZImage(xyz_image_32F3);
01140 //#endif
01141 //
01147 //
01148 //      return ipa_Utils::RET_OK;
01149 //}
01150 
01151 
01152 unsigned long CobFaceDetectionNodelet::convertColorImageMessageToMat(const sensor_msgs::Image::ConstPtr& color_image_msg, cv_bridge::CvImageConstPtr& color_image_ptr,
01153                 cv::Mat& color_image)
01154 {
01155         try
01156         {
01157                 color_image_ptr = cv_bridge::toCvShare(color_image_msg, sensor_msgs::image_encodings::BGR8);
01158         } catch (cv_bridge::Exception& e)
01159         {
01160                 ROS_ERROR("PeopleDetection: cv_bridge exception: %s", e.what());
01161                 return ipa_Utils::RET_FAILED;
01162         }
01163         color_image = color_image_ptr->image;
01164 
01165         return ipa_Utils::RET_OK;
01166 }
01167 
01168 unsigned long CobFaceDetectionNodelet::convertPclMessageToMat(const sensor_msgs::PointCloud2::ConstPtr& shared_image_msg, cv::Mat& depth_image)
01169 {
01170         pcl::PointCloud < pcl::PointXYZ > depth_cloud; // point cloud
01171         pcl::fromROSMsg(*shared_image_msg, depth_cloud);
01172         depth_image.create(depth_cloud.height, depth_cloud.width, CV_32FC3);
01173         uchar* depth_image_ptr = (uchar*)depth_image.data;
01174         for (int v = 0; v < (int)depth_cloud.height; v++)
01175         {
01176                 int baseIndex = depth_image.step * v;
01177                 for (int u = 0; u < (int)depth_cloud.width; u++)
01178                 {
01179                         int index = baseIndex + 3 * u * sizeof(float);
01180                         float* data_ptr = (float*)(depth_image_ptr + index);
01181                         pcl::PointXYZ point_xyz = depth_cloud(u, v);
01182                         data_ptr[0] = point_xyz.x;
01183                         data_ptr[1] = point_xyz.y;
01184                         data_ptr[2] = (isnan(point_xyz.z)) ? 0.f : point_xyz.z;
01185                         //if (u%100 == 0) std::cout << "u" << u << " v" << v << " z" << data_ptr[2] << "\n";
01186                 }
01187         }
01188         return ipa_Utils::RET_OK;
01189 }
01190 
01191 inline std::string CobFaceDetectionNodelet::getLabel(int index)
01192 {
01193         switch (index)
01194         {
01195         case -1:
01196                 // Distance to face class is too high
01197                 return "Unknown";
01198                 break;
01199         case -2:
01200                 // Distance to face space is too high
01201                 return "No face";
01202                 break;
01203         default:
01204                 // Face classified
01205                 return id_unique_[index];
01206         }
01207 }
01208 
01209 inline int abs(int x)
01210 {
01211         return ((x < 0) ? -x : x);
01212 }
01213 
01214 void CobFaceDetectionNodelet::recognizeCallback(const sensor_msgs::PointCloud2::ConstPtr& shared_image_msg, const sensor_msgs::Image::ConstPtr& color_image_msg)
01215 {
01216         // check if this is a training call
01217         if (train_continuous_server_running_ == true)
01218         {
01219                 trainContinuousCallback(shared_image_msg, color_image_msg);
01220                 return;
01221         }
01222 
01223         // check for disabled recognition
01224         if (recognize_server_running_ == false)
01225                 return;
01226 
01227         // convert input to cv::Mat images
01228         // color
01229         cv_bridge::CvImageConstPtr color_image_ptr;
01230         cv::Mat color_image;
01231         convertColorImageMessageToMat(color_image_msg, color_image_ptr, color_image);//color_image_ptr->image;
01232 
01233         // point cloud
01234         cv::Mat depth_image;
01235         convertPclMessageToMat(shared_image_msg, depth_image);
01236 
01237 #ifdef __LINUX__
01238         color_image_ = color_image;
01239         range_image_ = depth_image;
01240 #else
01241         // convert point cloud and color image to colored point cloud
01242         colored_pc_->SetColorImage(color_image);
01243         colored_pc_->SetXYZImage(depth_image);
01244 #endif
01245         //getMeasurement(shared_image_msg, color_image_msg);
01246 
01247         // todo: should not be necessary here (e.g. set a trained flag)
01248         PCA();
01249 
01250         if (eigen_vectors_.size() < 1)
01251         {
01252                 std::cout << "WARNING - PeopleDetector::ConsoleGUI:" << std::endl;
01253                 std::cout << "\t ... Less than two images are trained.\n";
01254                 return;
01255         }
01256 
01257         //DWORD start = timeGetTime();
01258         cv::Mat colorImage_8U3;
01259 #ifdef __LINUX__
01260         detectFaces(range_image_, color_image_);
01261         colorImage_8U3 = color_image_.clone();
01262 #else
01263         detectFaces(colored_pc_->GetXYZImage(), colored_pc_->GetColorImage());
01264         colored_pc_->GetColorImage().copyTo(colorImage_8U3);
01265 #endif
01266 
01267         std::vector<int> index;
01268         if (do_recognition_ == true)
01269         {
01270                 recognizeFace(color_image, index);
01271                 //std::cout << "INFO - PeopleDetector::Recognize:" << std::endl;
01272         }
01273         else
01274                 for (int i = 0; i < (int)color_faces_.size(); i++)
01275                         index.push_back(-1);
01276         //std::cout << "\t ... Recognize Time: " << (timeGetTime() - start) << std::endl;
01277 
01278         // publish face positions
01279         std::stringstream ss;
01280         ss << depth_image.rows << " " << depth_image.cols;
01281         cob_perception_msgs::DetectionArray facePositionMsg;
01282         // image dimensions
01283         facePositionMsg.header.frame_id = ss.str();
01284         // time stamp
01285         facePositionMsg.header.stamp = ros::Time::now(); //color_image_msg->header.stamp;  //
01286         //facePositionMsg.detections.reserve(color_faces_.size());
01287         // add all range faces that do not contain a face detection in the color image
01288         for (int i = 0; i < (int)range_faces_.size(); i++)
01289         {
01290                 // if no color face was detected in that region, add it to the published list
01291                 if (range_face_indices_with_color_face_detection_.find(i) == range_face_indices_with_color_face_detection_.end())
01292                 {
01293                         cv::Rect face = range_faces_[i];
01294 
01295                         // 2D image coordinates
01296                         cob_perception_msgs::Detection det;
01297                         det.mask.roi.x = face.x;
01298                         det.mask.roi.y = face.y;
01299                         det.mask.roi.width = face.width;
01300                         det.mask.roi.height = face.height;
01301                         float center2Dx = face.x + face.width * 0.5f;
01302                         float center2Dy = face.y + face.height * 0.5f;
01303 
01304                         // 3D world coordinates (and verify that the read pixel contained valid coordinates, otherwise search for valid pixel in neighborhood)
01305                         geometry_msgs::Point* point = &(det.pose.pose.position);
01306                         cv::Point3f p;
01307                         bool validCoordinates = false;
01308                         for (int d = 0; (d < 6 && !validCoordinates); d++)
01309                         {
01310                                 for (int v = -d; (v <= d && !validCoordinates); v++)
01311                                 {
01312                                         for (int u = -d; (u <= d && !validCoordinates); u++)
01313                                         {
01314                                                 if (abs(v) != d && abs(u) != d)
01315                                                         continue;
01316 
01317                                                 p = depth_image.at<cv::Point3f>(center2Dy + v, center2Dx + u);
01318                                                 point->x = p.x;
01319                                                 point->y = p.y;
01320                                                 point->z = p.z;
01321 
01322                                                 if (!isnan(point->x) && !isnan(point->y) && point->z != 0.f)
01323                                                         validCoordinates = true;
01324                                         }
01325                                 }
01326                         }
01327                         if (validCoordinates == false)
01328                                 continue;
01329 
01330                         // person ID
01331                         det.label = "UnknownRange";
01332 
01333                         // origin of detection
01334                         det.detector = "range";
01335 
01336                         facePositionMsg.detections.push_back(det);
01337                 }
01338         }
01339 
01340         // add all color face detections
01341         for (int i = 0; i < (int)color_faces_.size(); i++)
01342         {
01343                 cv::Rect face = color_faces_[i];
01344 
01345                 // 2D image coordinates
01346                 cob_perception_msgs::Detection det;
01347                 det.mask.roi.x = face.x;
01348                 det.mask.roi.y = face.y;
01349                 det.mask.roi.width = face.width;
01350                 det.mask.roi.height = face.height;
01351                 float center2Dx = face.x + face.width * 0.5f;
01352                 float center2Dy = face.y + face.height * 0.5f;
01353 
01354                 // 3D world coordinates
01355                 //              cv::Point3f p = depth_image.at<cv::Point3f>(center2Dy, center2Dx);
01356                 //              geometry_msgs::Point* point = &(det.pose.pose.position);
01357                 //              point->x = p.x; point->y=p.y; point->z=p.z;
01358 
01359                 // 3D world coordinates (and verify that the read pixel contained valid coordinates, otherwise search for valid pixel in neighborhood)
01360                 geometry_msgs::Point* point = &(det.pose.pose.position);
01361                 cv::Point3f p;
01362                 bool validCoordinates = false;
01363                 for (int d = 0; (d < 6 && !validCoordinates); d++)
01364                 {
01365                         for (int v = -d; (v <= d && !validCoordinates); v++)
01366                         {
01367                                 for (int u = -d; (u <= d && !validCoordinates); u++)
01368                                 {
01369                                         if (abs(v) != d && abs(u) != d)
01370                                                 continue;
01371 
01372                                         p = depth_image.at<cv::Point3f>(center2Dy + v, center2Dx + u);
01373                                         point->x = p.x;
01374                                         point->y = p.y;
01375                                         point->z = p.z;
01376 
01377                                         if (!isnan(point->x) && !isnan(point->y) && point->z != 0.f)
01378                                                 validCoordinates = true;
01379                                 }
01380                         }
01381                 }
01382                 if (validCoordinates == false)
01383                         continue;
01384 
01385                 // person ID
01386                 det.label = getLabel(index[i]);
01387 
01388                 // origin of detection
01389                 det.detector = "color";
01390 
01391                 facePositionMsg.detections.push_back(det);
01392         }
01393         face_position_publisher_.publish(facePositionMsg);
01394 
01395         //      std_msgs::Float32MultiArrayPtr facePositionMsg(new std_msgs::Float32MultiArray);
01396         //      const int dataBlockSize = 8;
01397         //      std::vector<float> data(dataBlockSize*color_faces_.size());
01398         //      for(int i=0; i<(int)color_faces_.size(); i++)
01399         //      {
01400         //              cv::Rect face = color_faces_[i];
01401         //              int baseIndex = i*dataBlockSize;
01402         //
01403         //              // 2D image coordinates
01404         //              data[baseIndex]=face.x; data[baseIndex+1]=face.y; data[baseIndex+2]=face.width; data[baseIndex+3]=face.height;
01405         //              float center2Dx = face.x + face.width*0.5f;
01406         //              float center2Dy = face.y + face.height*0.5f;
01407         //
01408         //              // 3D world coordinates
01409         //              cv::Point3f p = depth_image.at<cv::Point3f>(center2Dy, center2Dx);
01410         //              data[baseIndex+4]=p.x; data[baseIndex+5]=p.y; data[baseIndex+6]=p.z;
01411         //
01412         //              // person ID
01413         //              data[baseIndex+7]=index[i];
01414         //      }
01415         //      facePositionMsg->data = data;
01416         //      std::vector<std_msgs::MultiArrayDimension> dim(2, std_msgs::MultiArrayDimension());
01417         //      dim[0].label = "faces";       dim[0].size = color_faces_.size();        dim[0].stride = data.size();
01418         //      dim[1].label = "coordinates"; dim[1].size = dataBlockSize;          dim[1].stride = dataBlockSize;
01419         //      std_msgs::MultiArrayLayout layout;
01420         //      layout.dim = dim;
01421         //      layout.data_offset = 0;
01422         //      facePositionMsg->layout = layout;
01423         //      face_position_publisher_->publish(facePositionMsg);
01424 
01425         // display results
01426         if (display_ == true)
01427         {
01428                 for (int i = 0; i < (int)range_faces_.size(); i++)
01429                 {
01430                         cv::Rect face = range_faces_[i];
01431                         cv::rectangle(colorImage_8U3, cv::Point(face.x, face.y), cv::Point(face.x + face.width, face.y + face.height), CV_RGB(0, 0, 255), 2, 8, 0);
01432                 }
01433 
01434                 for (int i = 0; i < (int)color_faces_.size(); i++)
01435                 {
01436                         cv::Rect face = color_faces_[i];
01437 
01438                         cv::rectangle(colorImage_8U3, cv::Point(face.x, face.y), cv::Point(face.x + face.width, face.y + face.height), CV_RGB(0, 255, 0), 2, 8, 0);
01439 
01440                         std::stringstream tmp;
01441                         switch (index[i])
01442                         {
01443                         case -1:
01444                                 // Distance to face class is too high
01445                                 tmp << "Unknown";
01446                                 cv::putText(colorImage_8U3, tmp.str().c_str(), cv::Point(face.x, face.y + face.height + 25), cv::FONT_HERSHEY_PLAIN, 2, CV_RGB( 255, 0, 0 ), 2);
01447                                 break;
01448                         case -2:
01449                                 // Distance to face space is too high
01450                                 tmp << "No face";
01451                                 cv::putText(colorImage_8U3, tmp.str().c_str(), cv::Point(face.x, face.y + face.height + 25), cv::FONT_HERSHEY_PLAIN, 2, CV_RGB( 255, 0, 0 ), 2);
01452                                 break;
01453                         default:
01454                                 // Face classified
01455                                 tmp << id_unique_[index[i]].c_str();
01456                                 cv::putText(colorImage_8U3, tmp.str().c_str(), cv::Point(face.x, face.y + face.height + 25), cv::FONT_HERSHEY_PLAIN, 2, CV_RGB( 0, 255, 0 ), 2);
01457                         }
01458                 }
01459                 //cv::imshow("Face Detector", colorImage_8U3);
01460                 //cv::waitKey(10);
01461                 // publish topic
01462                 cv_bridge::CvImage cv_ptr;
01463                 cv_ptr.image = colorImage_8U3;
01464                 cv_ptr.encoding = "bgr8";
01465                 face_detection_image_pub_.publish(cv_ptr.toImageMsg());
01466         }
01467 }
01468 
01469 void CobFaceDetectionNodelet::trainContinuousCallback(const sensor_msgs::PointCloud2::ConstPtr& shared_image_msg, const sensor_msgs::Image::ConstPtr& color_image_msg)
01470 {
01471         if (train_continuous_server_running_ == false)
01472                 return;
01473 
01474         // convert input to cv::Mat images
01475         // color
01476         cv_bridge::CvImageConstPtr color_image_ptr;
01477         cv::Mat color_image;
01478         convertColorImageMessageToMat(color_image_msg, color_image_ptr, color_image);//color_image_ptr->image;
01479 
01480         // point cloud
01481         cv::Mat depth_image;
01482         convertPclMessageToMat(shared_image_msg, depth_image);
01483 
01484 #ifdef __LINUX__
01485         color_image_ = color_image;
01486         range_image_ = depth_image;
01487 #else
01488         // convert point cloud and color image to colored point cloud
01489         colored_pc_->SetColorImage(color_image);
01490         colored_pc_->SetXYZImage(depth_image);
01491 #endif
01492         //getMeasurement(shared_image_msg, color_image_msg);
01493 
01494         cv::Mat colorImage_8U3;
01495 #ifdef __LINUX__
01496         detectFaces(range_image_, color_image_);
01497         colorImage_8U3 = color_image_.clone();
01498 #else
01499         detectFaces(colored_pc_->GetXYZImage(), colored_pc_->GetColorImage());
01500         colored_pc_->GetColorImage().copyTo(colorImage_8U3);
01501 #endif
01502 
01503         for (int i = 0; i < (int)color_faces_.size(); i++)
01504         {
01505                 cv::Rect face = color_faces_[i];
01506                 cv::rectangle(colorImage_8U3, cv::Point(face.x, face.y), cv::Point(face.x + face.width, face.y + face.height), CV_RGB( 0, 255, 0 ), 2, 8, 0);
01507         }
01508 
01509         //cv::imshow("Face Recognizer Training", colorImage_8U3);
01510         //cv::waitKey(10);
01511         // publish topic
01512         cv_bridge::CvImage cv_ptr;
01513         cv_ptr.image = colorImage_8U3;
01514         cv_ptr.encoding = "bgr8";
01515         face_detection_image_pub_.publish(cv_ptr.toImageMsg());
01516 
01517         // capture image if triggered by an action
01518         // secure this section with a mutex
01519         boost::timed_mutex::scoped_timed_lock lock(action_mutex_, boost::posix_time::milliseconds(10));
01520         if (lock.owns_lock() && capture_training_face_ == true)
01521         {
01522                 capture_training_face_ = false;
01523 
01524                 // Check if there is more than one face detected
01525                 if (color_faces_.size() > 1)
01526                 {
01527                         std::cout << "WARNING - CobFaceDetectionNodelet::trainContinuousCallback:" << std::endl;
01528                         std::cout << "\t ... More than one faces are detected in image. Please try again." << std::endl;
01529                         return;
01530                 }
01531 
01532                 // Check if there is less than one face detected
01533                 if (color_faces_.size() < 1)
01534                 {
01535                         std::cout << "WARNING - CobFaceDetectionNodelet::trainContinuousCallback:" << std::endl;
01536                         std::cout << "\t ... Less than one faces are detected in image. Please try again." << std::endl;
01537                         return;
01538                 }
01539 
01540 #ifdef __LINUX__
01541                 addFace(color_image_, current_training_id_);
01542 #else
01543                 addFace(colored_pc_->GetColorImage(), current_training_id_);
01544 #endif
01545                 number_training_images_captured_++;
01546                 std::cout << "INFO - CuiPeopleDetector::ConsoleGUI:" << std::endl;
01547                 std::cout << "\t ... Face captured (" << face_images_.size() << ")." << std::endl;
01548         }
01549 }
01550 
01551 unsigned long CobFaceDetectionNodelet::loadParameters(const char* iniFileName)
01552 {
01554         TiXmlDocument* p_configXmlDocument = new TiXmlDocument(iniFileName);
01555         if (!p_configXmlDocument->LoadFile())
01556         {
01557                 std::cerr << "ERROR - PeopleDetector::LoadParameters:" << std::endl;
01558                 std::cerr << "\t ... Error while loading xml configuration file" << std::endl;
01559                 std::cerr << "\t ... (Check filename and syntax of the file):" << std::endl;
01560                 std::cerr << "\t ... '" << iniFileName << "'" << std::endl;
01561                 return ipa_Utils::RET_FAILED;
01562         }
01563         std::cout << "INFO - PeopleDetector::LoadParameters:" << std::endl;
01564         std::cout << "\t ... Parsing xml configuration file:" << std::endl;
01565         std::cout << "\t ... '" << iniFileName << "'" << std::endl;
01566 
01567         if (p_configXmlDocument)
01568         {
01569 
01570                 //************************************************************************************
01571                 //      BEGIN PeopleDetector
01572                 //************************************************************************************
01573                 // Tag element "PeopleDetector" of Xml Inifile
01574                 TiXmlElement *p_xmlElement_Root = NULL;
01575                 p_xmlElement_Root = p_configXmlDocument->FirstChildElement("PeopleDetector");
01576 
01577                 if (p_xmlElement_Root)
01578                 {
01579 
01580                         //************************************************************************************
01581                         //      BEGIN PeopleDetector->adaBoost
01582                         //************************************************************************************
01583                         // Tag element "adaBoost" of Xml Inifile
01584                         TiXmlElement *p_xmlElement_Root_OD = NULL;
01585                         p_xmlElement_Root_OD = p_xmlElement_Root->FirstChildElement("adaBoost");
01586 
01587                         if (p_xmlElement_Root_OD)
01588                         {
01589 
01590                                 //************************************************************************************
01591                                 //      BEGIN PeopleDetector->adaBoost->Faces_increase_search_scale
01592                                 //************************************************************************************
01593                                 // Subtag element "adaBoost" of Xml Inifile
01594                                 TiXmlElement *p_xmlElement_Child = NULL;
01595                                 p_xmlElement_Child = p_xmlElement_Root_OD->FirstChildElement("Faces_increase_search_scale");
01596 
01597                                 if (p_xmlElement_Child)
01598                                 {
01599                                         // read and save value of attribute
01600                                         if (p_xmlElement_Child->QueryValueAttribute("value", &people_detector_->m_faces_increase_search_scale) != TIXML_SUCCESS)
01601                                         {
01602                                                 std::cerr << "ERROR - PeopleDetector::LoadParameters:" << std::endl;
01603                                                 std::cerr << "\t ... Can't find attribute 'value' of tag 'Faces_increase_search_scale'" << std::endl;
01604                                                 return ipa_Utils::RET_FAILED;
01605                                         }
01606                                 }
01607                                 else
01608                                 {
01609                                         std::cerr << "ERROR - PeopleDetector::LoadParameters:" << std::endl;
01610                                         std::cerr << "\t ... Can't find tag 'Faces_increase_search_scale'" << std::endl;
01611                                         return ipa_Utils::RET_FAILED;
01612                                 }
01613 
01614                                 //************************************************************************************
01615                                 //      BEGIN PeopleDetector->adaBoost->Faces_drop_groups
01616                                 //************************************************************************************
01617                                 // Subtag element "adaBoost" of Xml Inifile
01618                                 p_xmlElement_Child = NULL;
01619                                 p_xmlElement_Child = p_xmlElement_Root_OD->FirstChildElement("Faces_drop_groups");
01620 
01621                                 if (p_xmlElement_Child)
01622                                 {
01623                                         // read and save value of attribute
01624                                         if (p_xmlElement_Child->QueryValueAttribute("value", &people_detector_->m_faces_drop_groups) != TIXML_SUCCESS)
01625                                         {
01626                                                 std::cerr << "ERROR - PeopleDetector::LoadParameters:" << std::endl;
01627                                                 std::cerr << "\t ... Can't find attribute 'value' of tag 'Faces_drop_groups'" << std::endl;
01628                                                 return ipa_Utils::RET_FAILED;
01629                                         }
01630                                 }
01631                                 else
01632                                 {
01633                                         std::cerr << "ERROR - PeopleDetector::LoadParameters:" << std::endl;
01634                                         std::cerr << "\t ... Can't find tag 'Faces_drop_groups'" << std::endl;
01635                                         return ipa_Utils::RET_FAILED;
01636                                 }
01637 
01638                                 //************************************************************************************
01639                                 //      BEGIN PeopleDetector->adaBoost->Faces_min_search_scale_x
01640                                 //************************************************************************************
01641                                 // Subtag element "adaBoost" of Xml Inifile
01642                                 p_xmlElement_Child = NULL;
01643                                 p_xmlElement_Child = p_xmlElement_Root_OD->FirstChildElement("Faces_min_search_scale_x");
01644 
01645                                 if (p_xmlElement_Child)
01646                                 {
01647                                         // read and save value of attribute
01648                                         if (p_xmlElement_Child->QueryValueAttribute("value", &people_detector_->m_faces_min_search_scale_x) != TIXML_SUCCESS)
01649                                         {
01650                                                 std::cerr << "ERROR - PeopleDetector::LoadParameters:" << std::endl;
01651                                                 std::cerr << "\t ... Can't find attribute 'value' of tag 'Faces_min_search_scale_x'" << std::endl;
01652                                                 return ipa_Utils::RET_FAILED;
01653                                         }
01654                                 }
01655                                 else
01656                                 {
01657                                         std::cerr << "ERROR - PeopleDetector::LoadParameters:" << std::endl;
01658                                         std::cerr << "\t ... Can't find tag 'Faces_min_search_scale_x'" << std::endl;
01659                                         return ipa_Utils::RET_FAILED;
01660                                 }
01661 
01662                                 //************************************************************************************
01663                                 //      BEGIN PeopleDetector->adaBoost->Faces_min_search_scale_y
01664                                 //************************************************************************************
01665                                 // Subtag element "adaBoost" of Xml Inifile
01666                                 p_xmlElement_Child = NULL;
01667                                 p_xmlElement_Child = p_xmlElement_Root_OD->FirstChildElement("Faces_min_search_scale_y");
01668 
01669                                 if (p_xmlElement_Child)
01670                                 {
01671                                         // read and save value of attribute
01672                                         if (p_xmlElement_Child->QueryValueAttribute("value", &people_detector_->m_faces_min_search_scale_y) != TIXML_SUCCESS)
01673                                         {
01674                                                 std::cerr << "ERROR - PeopleDetector::LoadParameters:" << std::endl;
01675                                                 std::cerr << "\t ... Can't find attribute 'value' of tag 'Faces_min_search_scale_y'" << std::endl;
01676                                                 return ipa_Utils::RET_FAILED;
01677                                         }
01678                                 }
01679                                 else
01680                                 {
01681                                         std::cerr << "ERROR - PeopleDetector::LoadParameters:" << std::endl;
01682                                         std::cerr << "\t ... Can't find tag 'Faces_min_search_scale_y'" << std::endl;
01683                                         return ipa_Utils::RET_FAILED;
01684                                 }
01685 
01686                                 //************************************************************************************
01687                                 //      BEGIN PeopleDetector->adaBoost->Range_increase_search_scale
01688                                 //************************************************************************************
01689                                 // Subtag element "adaBoost" of Xml Inifile
01690                                 p_xmlElement_Child = NULL;
01691                                 p_xmlElement_Child = p_xmlElement_Root_OD->FirstChildElement("Range_increase_search_scale");
01692 
01693                                 if (p_xmlElement_Child)
01694                                 {
01695                                         // read and save value of attribute
01696                                         if (p_xmlElement_Child->QueryValueAttribute("value", &people_detector_->m_range_increase_search_scale) != TIXML_SUCCESS)
01697                                         {
01698                                                 std::cerr << "ERROR - PeopleDetector::LoadParameters:" << std::endl;
01699                                                 std::cerr << "\t ... Can't find attribute 'value' of tag 'Range_increase_search_scale'" << std::endl;
01700                                                 return ipa_Utils::RET_FAILED;
01701                                         }
01702                                 }
01703                                 else
01704                                 {
01705                                         std::cerr << "ERROR - PeopleDetector::LoadParameters:" << std::endl;
01706                                         std::cerr << "\t ... Can't find tag 'Range_increase_search_scale'" << std::endl;
01707                                         return ipa_Utils::RET_FAILED;
01708                                 }
01709 
01710                                 //************************************************************************************
01711                                 //      BEGIN PeopleDetector->adaBoost->Range_drop_groups
01712                                 //************************************************************************************
01713                                 // Subtag element "adaBoost" of Xml Inifile
01714                                 p_xmlElement_Child = NULL;
01715                                 p_xmlElement_Child = p_xmlElement_Root_OD->FirstChildElement("Range_drop_groups");
01716 
01717                                 if (p_xmlElement_Child)
01718                                 {
01719                                         // read and save value of attribute
01720                                         if (p_xmlElement_Child->QueryValueAttribute("value", &people_detector_->m_range_drop_groups) != TIXML_SUCCESS)
01721                                         {
01722                                                 std::cerr << "ERROR - PeopleDetector::LoadParameters:" << std::endl;
01723                                                 std::cerr << "\t ... Can't find attribute 'value' of tag 'Range_drop_groups'" << std::endl;
01724                                                 return ipa_Utils::RET_FAILED;
01725                                         }
01726                                 }
01727                                 else
01728                                 {
01729                                         std::cerr << "ERROR - PeopleDetector::LoadParameters:" << std::endl;
01730                                         std::cerr << "\t ... Can't find tag 'Range_drop_groups'" << std::endl;
01731                                         return ipa_Utils::RET_FAILED;
01732                                 }
01733 
01734                                 //************************************************************************************
01735                                 //      BEGIN PeopleDetector->adaBoost->Range_min_search_scale_x
01736                                 //************************************************************************************
01737                                 // Subtag element "adaBoost" of Xml Inifile
01738                                 p_xmlElement_Child = NULL;
01739                                 p_xmlElement_Child = p_xmlElement_Root_OD->FirstChildElement("Range_min_search_scale_x");
01740 
01741                                 if (p_xmlElement_Child)
01742                                 {
01743                                         // read and save value of attribute
01744                                         if (p_xmlElement_Child->QueryValueAttribute("value", &people_detector_->m_range_min_search_scale_x) != TIXML_SUCCESS)
01745                                         {
01746                                                 std::cerr << "ERROR - PeopleDetector::LoadParameters:" << std::endl;
01747                                                 std::cerr << "\t ... Can't find attribute 'value' of tag 'Range_min_search_scale_x'" << std::endl;
01748                                                 return ipa_Utils::RET_FAILED;
01749                                         }
01750                                 }
01751                                 else
01752                                 {
01753                                         std::cerr << "ERROR - PeopleDetector::LoadParameters:" << std::endl;
01754                                         std::cerr << "\t ... Can't find tag 'Range_min_search_scale_x'" << std::endl;
01755                                         return ipa_Utils::RET_FAILED;
01756                                 }
01757 
01758                                 //************************************************************************************
01759                                 //      BEGIN PeopleDetector->adaBoost->Range_min_search_scale_y
01760                                 //************************************************************************************
01761                                 // Subtag element "adaBoost" of Xml Inifile
01762                                 p_xmlElement_Child = NULL;
01763                                 p_xmlElement_Child = p_xmlElement_Root_OD->FirstChildElement("Range_min_search_scale_y");
01764 
01765                                 if (p_xmlElement_Child)
01766                                 {
01767                                         // read and save value of attribute
01768                                         if (p_xmlElement_Child->QueryValueAttribute("value", &people_detector_->m_range_min_search_scale_y) != TIXML_SUCCESS)
01769                                         {
01770                                                 std::cerr << "ERROR - PeopleDetector::LoadParameters:" << std::endl;
01771                                                 std::cerr << "\t ... Can't find attribute 'value' of tag 'Range_min_search_scale_y'" << std::endl;
01772                                                 return ipa_Utils::RET_FAILED;
01773                                         }
01774                                 }
01775                                 else
01776                                 {
01777                                         std::cerr << "ERROR - PeopleDetector::LoadParameters:" << std::endl;
01778                                         std::cerr << "\t ... Can't find tag 'Range_min_search_scale_y'" << std::endl;
01779                                         return ipa_Utils::RET_FAILED;
01780                                 }
01781                         }
01782                         //************************************************************************************
01783                         //      END CameraDataViewerControlFlow->adaBoost
01784                         //************************************************************************************
01785 
01786                         //************************************************************************************
01787                         //      BEGIN PeopleDetector->eigenfaces
01788                         //************************************************************************************
01789                         // Tag element "adaBoost" of Xml Inifile
01790                         p_xmlElement_Root_OD = NULL;
01791                         p_xmlElement_Root_OD = p_xmlElement_Root->FirstChildElement("eigenfaces");
01792 
01793                         if (p_xmlElement_Root_OD)
01794                         {
01795 
01796                                 //************************************************************************************
01797                                 //      BEGIN PeopleDetector->eigenfaces->Threshold_Face_Class
01798                                 //************************************************************************************
01799                                 // Subtag element "adaBoost" of Xml Inifile
01800                                 TiXmlElement *p_xmlElement_Child = NULL;
01801                                 p_xmlElement_Child = p_xmlElement_Root_OD->FirstChildElement("Threshold_Face_Class");
01802 
01803                                 if (p_xmlElement_Child)
01804                                 {
01805                                         // read and save value of attribute
01806                                         if (p_xmlElement_Child->QueryValueAttribute("value", &threshold_) != TIXML_SUCCESS)
01807                                         {
01808                                                 std::cerr << "ERROR - PeopleDetector::LoadParameters:" << std::endl;
01809                                                 std::cerr << "\t ... Can't find attribute 'value' of tag 'Threshold_Face_Class'" << std::endl;
01810                                                 return ipa_Utils::RET_FAILED;
01811                                         }
01812                                 }
01813                                 else
01814                                 {
01815                                         std::cerr << "ERROR - PeopleDetector::LoadParameters:" << std::endl;
01816                                         std::cerr << "\t ... Can't find tag 'Threshold_Face_Class'" << std::endl;
01817                                         return ipa_Utils::RET_FAILED;
01818                                 }
01819                                 //************************************************************************************
01820                                 //      BEGIN PeopleDetector->eigenfaces->Threshold_Facespace
01821                                 //************************************************************************************
01822                                 // Subtag element "adaBoost" of Xml Inifile
01823                                 p_xmlElement_Child = NULL;
01824                                 p_xmlElement_Child = p_xmlElement_Root_OD->FirstChildElement("Threshold_Facespace");
01825 
01826                                 if (p_xmlElement_Child)
01827                                 {
01828                                         // read and save value of attribute
01829                                         if (p_xmlElement_Child->QueryValueAttribute("value", &threshold_fs_) != TIXML_SUCCESS)
01830                                         {
01831                                                 std::cerr << "ERROR - PeopleDetector::LoadParameters:" << std::endl;
01832                                                 std::cerr << "\t ... Can't find attribute 'value' of tag 'Threshold_Facespace'" << std::endl;
01833                                                 return ipa_Utils::RET_FAILED;
01834                                         }
01835                                 }
01836                                 else
01837                                 {
01838                                         std::cerr << "ERROR - PeopleDetector::LoadParameters:" << std::endl;
01839                                         std::cerr << "\t ... Can't find tag 'Threshold_Facespace'" << std::endl;
01840                                         return ipa_Utils::RET_FAILED;
01841                                 }
01842                                 //************************************************************************************
01843                                 //      END CameraDataViewerControlFlow->eigenfaces
01844                                 //************************************************************************************
01845 
01846                         }
01847                         else
01848                         {
01849                                 std::cerr << "ERROR - CameraDataViewerControlFlow::LoadParameters:" << std::endl;
01850                                 std::cerr << "\t ... Can't find tag 'ObjectDetectorParameters'" << std::endl;
01851                                 return ipa_Utils::RET_FAILED;
01852                         }
01853 
01854                 }
01855 
01856                 //************************************************************************************
01857                 //      END ObjectDetector
01858                 //************************************************************************************
01859                 else
01860                 {
01861                         std::cerr << "ERROR - CameraDataViewerControlFlow::LoadParameters:" << std::endl;
01862                         std::cerr << "\t ... Can't find tag 'ObjectDetector'" << std::endl;
01863                         return ipa_Utils::RET_FAILED;
01864                 }
01865         }
01866         return ipa_Utils::RET_OK;
01867 }
01868 
01869 //#######################
01870 //#### main programm ####
01871 //int main(int argc, char** argv)
01872 //{
01873 //      // Initialize ROS, specify name of node
01874 //      ros::init(argc, argv, "people_detection");
01875 //
01876 //      // Create a handle for this node, initialize node
01877 //      ros::NodeHandle nh;
01878 //
01879 //      // Create people detection node class instance
01880 //      CobFaceDetectionNodelet people_detection_node(nh);
01881 //
01882 //      // Initialize people detection node
01883 //      if (people_detection_node.init() != ipa_Utils::RET_OK)
01884 //              return 0;
01885 //
01886 //      // Create action nodes
01887 //      //DetectObjectsAction detect_action_node(object_detection_node, nh);
01888 //      //AcquireObjectImageAction acquire_image_node(object_detection_node, nh);
01889 //      //TrainObjectAction train_object_node(object_detection_node, nh);
01890 //
01891 //      ros::spin();
01892 //
01893 //      return 0;
01894 //}
01895 


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