Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045
00046
00047
00048
00049
00050
00051
00052
00053
00054
00055 #ifndef _FACE_DETECTION_
00056 #define _FACE_DETECTION_
00057
00058
00059
00060
00061
00062
00063
00064
00065 #include <ros/ros.h>
00066 #include <nodelet/nodelet.h>
00067 #include <ros/package.h>
00068
00069 #include <actionlib/server/simple_action_server.h>
00070
00071
00072 #include <sensor_msgs/Image.h>
00073 #include <sensor_msgs/PointCloud2.h>
00074
00075 #include <cob_perception_msgs/DetectionArray.h>
00076
00077
00078 #include <message_filters/subscriber.h>
00079 #include <message_filters/synchronizer.h>
00080 #include <message_filters/sync_policies/approximate_time.h>
00081 #include <image_transport/image_transport.h>
00082 #include <image_transport/subscriber_filter.h>
00083
00084
00085 #include <cob_people_detection/Recognition.h>
00086
00087
00088 #include <actionlib/server/simple_action_server.h>
00089 #include <cob_people_detection/TrainContinuousAction.h>
00090 #include <cob_people_detection/TrainCaptureSampleAction.h>
00091 #include <cob_people_detection/RecognizeAction.h>
00092 #include <cob_people_detection/LoadAction.h>
00093 #include <cob_people_detection/SaveAction.h>
00094 #include <cob_people_detection/ShowAction.h>
00095
00096
00097 #include <opencv/cv.h>
00098 #include <opencv/ml.h>
00099 #include <cv_bridge/cv_bridge.h>
00100 #include <sensor_msgs/image_encodings.h>
00101
00102
00103 #include <pcl/point_types.h>
00104 #include <pcl_ros/point_cloud.h>
00105
00106
00107 #include "tinyxml.h"
00108
00109
00110 #include <boost/bind.hpp>
00111 #include <boost/thread/mutex.hpp>
00112 #include "boost/filesystem/operations.hpp"
00113 #include "boost/filesystem/convenience.hpp"
00114 #include "boost/filesystem/path.hpp"
00115 namespace fs = boost::filesystem;
00116
00117
00118 #ifdef __LINUX__
00119 #else
00120 #include "cob_vision_ipa_utils/MathUtils.h"
00121 #include "cob_sensor_fusion/ColoredPointCloudSequence.h"
00122 #endif
00123
00124 #include "cob_people_detection/people_detector.h"
00125
00126 #include <sstream>
00127 #include <string>
00128 #include <vector>
00129 #include <set>
00130
00131 namespace ipa_PeopleDetector
00132 {
00133
00134 typedef actionlib::SimpleActionServer<cob_people_detection::TrainContinuousAction> TrainContinuousServer;
00135 typedef actionlib::SimpleActionServer<cob_people_detection::TrainCaptureSampleAction> TrainCaptureSampleServer;
00136 typedef actionlib::SimpleActionServer<cob_people_detection::RecognizeAction> RecognizeServer;
00137 typedef actionlib::SimpleActionServer<cob_people_detection::LoadAction> LoadServer;
00138 typedef actionlib::SimpleActionServer<cob_people_detection::SaveAction> SaveServer;
00139 typedef actionlib::SimpleActionServer<cob_people_detection::ShowAction> ShowServer;
00140
00141
00142
00143 class CobFaceDetectionNodelet: public nodelet::Nodelet
00144 {
00145 protected:
00146 message_filters::Subscriber<sensor_msgs::PointCloud2> shared_image_sub_;
00147 image_transport::ImageTransport* it_;
00148 image_transport::SubscriberFilter color_camera_image_sub_;
00149 image_transport::Publisher face_detection_image_pub_;
00150 message_filters::Synchronizer<message_filters::sync_policies::ApproximateTime<sensor_msgs::PointCloud2, sensor_msgs::Image> >* sync_pointcloud_;
00151 message_filters::Connection sync_pointcloud_callback_connection_;
00152 ros::Publisher face_position_publisher_;
00153
00154 ros::NodeHandle node_handle_;
00155
00156 #ifdef __LINUX__
00157 cv::Mat color_image_;
00158 cv::Mat range_image_;
00159 #else
00160 ipa_SensorFusion::ColoredPointCloudPtr colored_pc_;
00161 #endif
00162
00163 std::string directory_;
00164 bool run_pca_;
00165 int filename_;
00166
00167 std::vector<cv::Mat> face_images_;
00168 std::vector<std::string> id_;
00169 std::vector<std::string> id_unique_;
00170
00171 int n_eigens_;
00172 std::vector<cv::Mat> eigen_vectors_;
00173 cv::Mat eigen_val_mat_;
00174 cv::Mat avg_image_;
00175 cv::Mat projected_train_face_mat_;
00176 cv::Mat face_class_avg_projections_;
00177 cv::SVM person_classifier_;
00178
00179 PeopleDetector* people_detector_;
00180 int threshold_;
00181 int threshold_fs_;
00182 std::vector<cv::Rect> color_faces_;
00183 std::vector<cv::Rect> range_faces_;
00184 std::set<size_t> range_face_indices_with_color_face_detection_;
00185
00186
00187 ros::ServiceServer recognize_service_server_;
00188
00189
00190 TrainContinuousServer* train_continuous_server_;
00191 TrainCaptureSampleServer* train_capture_sample_server_;
00192 RecognizeServer* recognize_server_;
00193 LoadServer* load_server_;
00194 SaveServer* save_server_;
00195 ShowServer* show_server_;
00196 bool occupied_by_action_;
00197 bool recognize_server_running_;
00198 bool train_continuous_server_running_;
00199 bool capture_training_face_;
00200 int number_training_images_captured_;
00201
00202 bool do_recognition_;
00203 bool display_;
00204
00205 std::string current_training_id_;
00206 boost::timed_mutex action_mutex_;
00207
00208
00209 static const double FACE_SIZE_MIN_M = 0.12;
00210 static const double FACE_SIZE_MAX_M = 0.35;
00211 static const double MAX_FACE_Z_M = 8.0;
00212
00213
00214 double face_size_min_m_;
00215 double face_size_max_m_;
00216 double max_face_z_m_;
00217 bool fill_unassigned_depth_values_;
00218 bool reason_about_3dface_size_;
00219
00220 public:
00221
00222 CobFaceDetectionNodelet();
00223
00224 ~CobFaceDetectionNodelet();
00225
00227 void onInit();
00228
00231 unsigned long init();
00232
00237 unsigned long detectFaces(cv::Mat& xyz_image, cv::Mat& color_image);
00238
00244 unsigned long recognizeFace(cv::Mat& color_image, std::vector<int>& index);
00245
00250 unsigned long addFace(cv::Mat& image, std::string id);
00251
00254 unsigned long PCA();
00255
00256 unsigned long saveAllData();
00257
00260 unsigned long saveTrainingData();
00261
00262 unsigned long saveRecognizerData();
00263
00266 unsigned long loadAllData();
00267
00271 unsigned long loadTrainingData(bool runPCA);
00272
00275 unsigned long loadRecognizerData();
00276
00281 unsigned long getEigenface(cv::Mat& eigenface, int index);
00282
00286 unsigned long showAVGImage(cv::Mat& avgImage);
00287
00291 unsigned long saveRangeTrainImages(cv::Mat& xyz_image);
00292
00293
00294
00295 unsigned long convertColorImageMessageToMat(const sensor_msgs::Image::ConstPtr& color_image_msg, cv_bridge::CvImageConstPtr& color_image_ptr, cv::Mat& color_image);
00296
00297 unsigned long convertPclMessageToMat(const sensor_msgs::PointCloud2::ConstPtr& shared_image_msg, cv::Mat& depth_image);
00298
00300 std::string getLabel(int index);
00301
00303 void recognizeCallback(const sensor_msgs::PointCloud2::ConstPtr& shared_image_msg, const sensor_msgs::Image::ConstPtr& color_image_msg);
00304
00305 bool recognizeServiceServerCallback(cob_people_detection::Recognition::Request &req, cob_people_detection::Recognition::Response &res);
00306
00308 void recognizeServerCallback(const cob_people_detection::RecognizeGoalConstPtr& goal);
00309
00310 void trainContinuousCallback(const sensor_msgs::PointCloud2::ConstPtr& shared_image_msg, const sensor_msgs::Image::ConstPtr& color_image_msg);
00311
00312 void trainContinuousServerCallback(const cob_people_detection::TrainContinuousGoalConstPtr& goal);
00313
00314 void trainCaptureSampleServerCallback(const cob_people_detection::TrainCaptureSampleGoalConstPtr& goal);
00315
00316 void loadServerCallback(const cob_people_detection::LoadGoalConstPtr& goal);
00317
00318 void saveServerCallback(const cob_people_detection::SaveGoalConstPtr& goal);
00319
00320 void showServerCallback(const cob_people_detection::ShowGoalConstPtr& goal);
00321
00322 unsigned long loadParameters(const char* iniFileName);
00323 };
00324
00325 }
00326 ;
00327
00328 #endif // _FACE_DETECTION_