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