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 #include <stdio.h>
00041 #include <iostream>
00042 #include <vector>
00043 #include <fstream>
00044
00045 #include <ros/ros.h>
00046 #include <boost/filesystem.hpp>
00047 #include <boost/thread/mutex.hpp>
00048
00049 #include <people_msgs/PositionMeasurement.h>
00050 #include <message_filters/subscriber.h>
00051 #include <message_filters/time_synchronizer.h>
00052 #include <image_transport/subscriber_filter.h>
00053 #include "sensor_msgs/CameraInfo.h"
00054 #include "sensor_msgs/Image.h"
00055 #include "stereo_msgs/DisparityImage.h"
00056 #include "cv_bridge/CvBridge.h"
00057 #include "tf/transform_listener.h"
00058 #include "sensor_msgs/PointCloud.h"
00059 #include "geometry_msgs/Point32.h"
00060
00061 #include "opencv/cxcore.hpp"
00062 #include "opencv/cv.hpp"
00063 #include "opencv/highgui.h"
00064
00065 #include "face_detector/faces.h"
00066
00067 #include "image_geometry/stereo_camera_model.h"
00068
00069 #include <actionlib/server/simple_action_server.h>
00070 #include <face_detector/FaceDetectorAction.h>
00071
00072 using namespace std;
00073
00074 namespace people {
00075
00078 class FaceDetector {
00079 public:
00080
00081 const double BIGDIST_M;
00082
00083
00084 ros::NodeHandle nh_;
00085
00086
00087 image_transport::ImageTransport it_;
00088 image_transport::SubscriberFilter limage_sub_;
00089 message_filters::Subscriber<stereo_msgs::DisparityImage> dimage_sub_;
00090 message_filters::Subscriber<sensor_msgs::CameraInfo> lcinfo_sub_;
00091 message_filters::Subscriber<sensor_msgs::CameraInfo> rcinfo_sub_;
00092 sensor_msgs::CvBridge lbridge_;
00093 sensor_msgs::CvBridge dbridge_;
00094 message_filters::TimeSynchronizer<sensor_msgs::Image, stereo_msgs::DisparityImage, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo> sync_;
00097
00098 actionlib::SimpleActionServer<face_detector::FaceDetectorAction> as_;
00099 face_detector::FaceDetectorFeedback feedback_;
00100 face_detector::FaceDetectorResult result_;
00101
00102
00103
00104 ros::Subscriber pos_sub_;
00105 bool external_init_;
00106
00107
00108
00109
00110
00111
00112 ros::Publisher cloud_pub_;
00113 ros::Publisher pos_pub_;
00114
00115
00116 string do_display_;
00117 cv::Mat cv_image_out_;
00119
00120 bool use_depth_;
00121 image_geometry::StereoCameraModel cam_model_;
00123
00124 Faces *faces_;
00125 string name_;
00126 string haar_filename_;
00127 double reliability_;
00129 struct RestampedPositionMeasurement {
00130 ros::Time restamp;
00131 people_msgs::PositionMeasurement pos;
00132 double dist;
00133 };
00134 map<string, RestampedPositionMeasurement> pos_list_;
00136 bool quit_;
00137
00138 tf::TransformListener tf_;
00139
00140 boost::mutex cv_mutex_, pos_mutex_, limage_mutex_, dimage_mutex_;
00141
00142 bool do_continuous_;
00144 bool do_publish_unknown_;
00146 FaceDetector(std::string name) :
00147 BIGDIST_M(1000000.0),
00148 it_(nh_),
00149 sync_(4),
00150 as_(nh_,name),
00151 faces_(0),
00152 quit_(false)
00153 {
00154 ROS_INFO_STREAM_NAMED("face_detector","Constructing FaceDetector.");
00155
00156 if (do_display_ == "local") {
00157
00158 cv::namedWindow("Face detector: Face Detection", CV_WINDOW_AUTOSIZE);
00159 }
00160
00161
00162
00163 as_.registerGoalCallback(boost::bind(&FaceDetector::goalCB, this));
00164 as_.registerPreemptCallback(boost::bind(&FaceDetector::preemptCB, this));
00165
00166 faces_ = new Faces();
00167 double face_size_min_m, face_size_max_m, max_face_z_m, face_sep_dist_m;
00168
00169
00170 ros::NodeHandle local_nh("~");
00171 local_nh.param("classifier_name",name_,std::string(""));
00172 local_nh.param("classifier_filename",haar_filename_,std::string(""));
00173 local_nh.param("classifier_reliability",reliability_,0.0);
00174 local_nh.param("do_display",do_display_,std::string("none"));
00175 local_nh.param("do_continuous",do_continuous_,true);
00176 local_nh.param("do_publish_faces_of_unknown_size",do_publish_unknown_,false);
00177 local_nh.param("use_depth",use_depth_,true);
00178 local_nh.param("use_external_init",external_init_,true);
00179 local_nh.param("face_size_min_m",face_size_min_m,Faces::FACE_SIZE_MIN_M);
00180 local_nh.param("face_size_max_m",face_size_max_m,Faces::FACE_SIZE_MAX_M);
00181 local_nh.param("max_face_z_m",max_face_z_m,Faces::MAX_FACE_Z_M);
00182 local_nh.param("face_separation_dist_m",face_sep_dist_m,Faces::FACE_SEP_DIST_M);
00183
00184 faces_->initFaceDetection(1, haar_filename_, face_size_min_m, face_size_max_m, max_face_z_m, face_sep_dist_m);
00185
00186
00187 string stereo_namespace, image_topic;
00188 stereo_namespace = nh_.resolveName("stereo");
00189 image_topic = nh_.resolveName("image");
00190 string left_topic = ros::names::clean(stereo_namespace + "/left/" + image_topic);
00191 string disparity_topic = ros::names::clean(stereo_namespace + "/disparity");
00192 string left_camera_info_topic = ros::names::clean(stereo_namespace + "/left/camera_info");
00193 string right_camera_info_topic = ros::names::clean(stereo_namespace + "/right/camera_info");
00194 limage_sub_.subscribe(it_,left_topic,3);
00195 dimage_sub_.subscribe(nh_,disparity_topic,3);
00196 lcinfo_sub_.subscribe(nh_,left_camera_info_topic,3);
00197 rcinfo_sub_.subscribe(nh_,right_camera_info_topic,3);
00198 sync_.connectInput(limage_sub_, dimage_sub_, lcinfo_sub_, rcinfo_sub_),
00199 sync_.registerCallback(boost::bind(&FaceDetector::imageCBAll, this, _1, _2, _3, _4));
00200
00201
00202 pos_pub_ = nh_.advertise<people_msgs::PositionMeasurement>("face_detector/people_tracker_measurements",1);
00203
00204 cloud_pub_ = nh_.advertise<sensor_msgs::PointCloud>("face_detector/faces_cloud",0);
00205
00206
00207 if (external_init_) {
00208 pos_sub_ = nh_.subscribe("people_tracker_filter",1,&FaceDetector::posCallback,this);
00209 ROS_INFO_STREAM_NAMED("face_detector","Subscribed to the person filter messages.");
00210 }
00211
00212 ros::MultiThreadedSpinner s(2);
00213 ros::spin(s);
00214
00215 }
00216
00217 ~FaceDetector()
00218 {
00219
00220 cv_image_out_.release();
00221
00222 if (do_display_ == "local") {
00223 cv::destroyWindow("Face detector: Face Detection");
00224 }
00225
00226 if (faces_) {delete faces_; faces_ = 0;}
00227 }
00228
00229 void goalCB() {
00230 ROS_INFO("Face detector action started.");
00231 as_.acceptNewGoal();
00232 }
00233
00234 void preemptCB() {
00235 ROS_INFO("Face detector action preempted.");
00236 as_.setPreempted();
00237 }
00238
00239
00246 void posCallback(const people_msgs::PositionMeasurementConstPtr& pos_ptr) {
00247
00248
00249 boost::mutex::scoped_lock lock(pos_mutex_);
00250 map<string, RestampedPositionMeasurement>::iterator it;
00251 it = pos_list_.find(pos_ptr->object_id);
00252 RestampedPositionMeasurement rpm;
00253 rpm.pos = *pos_ptr;
00254 rpm.restamp = pos_ptr->header.stamp;
00255 rpm.dist = BIGDIST_M;
00256 if (it == pos_list_.end()) {
00257 pos_list_.insert(pair<string, RestampedPositionMeasurement>(pos_ptr->object_id, rpm));
00258 }
00259 else if ((pos_ptr->header.stamp - (*it).second.pos.header.stamp) > ros::Duration().fromSec(-1.0) ){
00260 (*it).second = rpm;
00261 }
00262 lock.unlock();
00263
00264 }
00265
00266
00267 struct NullDeleter
00268 {
00269 void operator()(void const *) const {}
00270 };
00271
00272
00281 void imageCBAll(const sensor_msgs::Image::ConstPtr &limage, const stereo_msgs::DisparityImage::ConstPtr& dimage, const sensor_msgs::CameraInfo::ConstPtr& lcinfo, const sensor_msgs::CameraInfo::ConstPtr& rcinfo)
00282 {
00283
00284
00285 if (!do_continuous_ && !as_.isActive())
00286 return;
00287
00288
00289
00290 result_.face_positions.clear();
00291
00292 if (do_display_ == "local") {
00293 cv_mutex_.lock();
00294 }
00295
00296
00297 cv::Mat cv_image_left(lbridge_.imgMsgToCv(limage,"bgr8"));
00298 sensor_msgs::ImageConstPtr boost_dimage(const_cast<sensor_msgs::Image*>(&dimage->image), NullDeleter());
00299 cv::Mat cv_image_disp(dbridge_.imgMsgToCv(boost_dimage));
00300 cam_model_.fromCameraInfo(lcinfo,rcinfo);
00301
00302
00303 if (do_display_ == "local") {
00304 cv_image_out_ = cv_image_left.clone();
00305 }
00306
00307 struct timeval timeofday;
00308 gettimeofday(&timeofday,NULL);
00309 ros::Time starttdetect = ros::Time().fromNSec(1e9*timeofday.tv_sec + 1e3*timeofday.tv_usec);
00310
00311 vector<Box2D3D> faces_vector = faces_->detectAllFaces(cv_image_left, 1.0, cv_image_disp, &cam_model_);
00312 gettimeofday(&timeofday,NULL);
00313 ros::Time endtdetect = ros::Time().fromNSec(1e9*timeofday.tv_sec + 1e3*timeofday.tv_usec);
00314 ros::Duration diffdetect = endtdetect - starttdetect;
00315 ROS_DEBUG_STREAM_NAMED("face_detector","Detection duration = " << diffdetect.toSec() << "sec");
00316
00317
00318 bool found_faces = false;
00319
00320 int ngood = 0;
00321 sensor_msgs::PointCloud cloud;
00322 cloud.header.stamp = limage->header.stamp;
00323 cloud.header.frame_id = limage->header.frame_id;
00324
00325 if (faces_vector.size() > 0 ) {
00326
00327
00328 boost::mutex::scoped_lock pos_lock(pos_mutex_);
00329 map<string, RestampedPositionMeasurement>::iterator it;
00330 for (it = pos_list_.begin(); it != pos_list_.end(); it++) {
00331 if ((limage->header.stamp - (*it).second.restamp) > ros::Duration().fromSec(5.0)) {
00332
00333 pos_list_.erase(it);
00334 }
00335 else {
00336
00337 tf::Point pt;
00338 tf::pointMsgToTF((*it).second.pos.pos, pt);
00339 tf::Stamped<tf::Point> loc(pt, (*it).second.pos.header.stamp, (*it).second.pos.header.frame_id);
00340 try {
00341 tf_.transformPoint(limage->header.frame_id, limage->header.stamp, loc, "odom_combined", loc);
00342 (*it).second.pos.header.stamp = limage->header.stamp;
00343 (*it).second.pos.pos.x = loc[0];
00344 (*it).second.pos.pos.y = loc[1];
00345 (*it).second.pos.pos.z = loc[2];
00346 }
00347 catch (tf::TransformException& ex) {
00348 }
00349 }
00350 }
00351
00352
00353
00354 Box2D3D *one_face;
00355 people_msgs::PositionMeasurement pos;
00356
00357 for (uint iface = 0; iface < faces_vector.size(); iface++) {
00358 one_face = &faces_vector[iface];
00359
00360 if (one_face->status=="good" || (one_face->status=="unknown" && do_publish_unknown_)) {
00361
00362 std::string id = "";
00363
00364
00365 pos.header.stamp = limage->header.stamp;
00366 pos.name = name_;
00367 pos.pos.x = one_face->center3d.x;
00368 pos.pos.y = one_face->center3d.y;
00369 pos.pos.z = one_face->center3d.z;
00370 pos.header.frame_id = limage->header.frame_id;
00371 pos.reliability = reliability_;
00372 pos.initialization = 1;
00373 pos.covariance[0] = 0.04; pos.covariance[1] = 0.0; pos.covariance[2] = 0.0;
00374 pos.covariance[3] = 0.0; pos.covariance[4] = 0.04; pos.covariance[5] = 0.0;
00375 pos.covariance[6] = 0.0; pos.covariance[7] = 0.0; pos.covariance[8] = 0.04;
00376
00377
00378
00379
00380 double dist, mindist = BIGDIST_M;
00381 map<string, RestampedPositionMeasurement>::iterator close_it = pos_list_.end();
00382 for (it = pos_list_.begin(); it != pos_list_.end(); it++) {
00383 dist = pow((*it).second.pos.pos.x - pos.pos.x, 2.0) + pow((*it).second.pos.pos.y - pos.pos.y, 2.0) + pow((*it).second.pos.pos.z - pos.pos.z, 2.0);
00384 if (dist <= faces_->face_sep_dist_m_ && dist < mindist) {
00385 mindist = dist;
00386 close_it = it;
00387 }
00388 }
00389 if (close_it != pos_list_.end()) {
00390 if (mindist < (*close_it).second.dist) {
00391 (*close_it).second.restamp = limage->header.stamp;
00392 (*close_it).second.dist = mindist;
00393 (*close_it).second.pos = pos;
00394 }
00395 pos.object_id = (*close_it).second.pos.object_id;
00396 ROS_INFO_STREAM_NAMED("face_detector","Found face " << pos.object_id);
00397 }
00398 else {
00399 pos.object_id = "";
00400 }
00401 result_.face_positions.push_back(pos);
00402 found_faces = true;
00403 pos_pub_.publish(pos);
00404
00405 }
00406
00407 }
00408 pos_lock.unlock();
00409
00410
00411 for (it = pos_list_.begin(); it != pos_list_.end(); it++) {
00412 (*it).second.dist = BIGDIST_M;
00413 }
00414
00415
00416
00417
00418
00419
00420 cloud.channels.resize(1);
00421 cloud.channels[0].name = "intensity";
00422
00423 for (uint iface = 0; iface < faces_vector.size(); iface++) {
00424 one_face = &faces_vector[iface];
00425
00426
00427 if (one_face->status == "good") {
00428
00429 geometry_msgs::Point32 p;
00430 p.x = one_face->center3d.x;
00431 p.y = one_face->center3d.y;
00432 p.z = one_face->center3d.z;
00433 cloud.points.push_back(p);
00434 cloud.channels[0].values.push_back(1.0f);
00435
00436 ngood ++;
00437 }
00438 else {
00439 ROS_DEBUG_STREAM_NAMED("face_detector","The detection didn't have a valid size, so it wasn't visualized.");
00440 }
00441
00442
00443 if (do_display_ == "local") {
00444 cv::Scalar color;
00445 if (one_face->status == "good") {
00446 color = cv::Scalar(0,255,0);
00447 }
00448 else if (one_face->status == "unknown") {
00449 color = cv::Scalar(255,0,0);
00450 }
00451 else {
00452 color = cv::Scalar(0,0,255);
00453 }
00454
00455 if (do_display_ == "local") {
00456 cv::rectangle(cv_image_out_,
00457 cv::Point(one_face->box2d.x,one_face->box2d.y),
00458 cv::Point(one_face->box2d.x+one_face->box2d.width, one_face->box2d.y+one_face->box2d.height), color, 4);
00459 }
00460 }
00461 }
00462
00463 }
00464
00465 cloud_pub_.publish(cloud);
00466
00467
00468 if (do_display_ == "local") {
00469
00470 cv::imshow("Face detector: Face Detection",cv_image_out_);
00471 cv::waitKey(2);
00472
00473 cv_mutex_.unlock();
00474 }
00475
00476
00477 ROS_INFO_STREAM_NAMED("face_detector","Number of faces found: " << faces_vector.size() << ", number with good depth and size: " << ngood);
00478
00479
00480
00481 if (!do_continuous_ && found_faces) {
00482 as_.setSucceeded(result_);
00483 }
00484
00485
00486 }
00487
00488 };
00489
00490 };
00491
00492
00493 int main(int argc, char **argv)
00494 {
00495 ros::init(argc,argv,"face_detector");
00496
00497 people::FaceDetector fd(ros::this_node::getName());
00498
00499 return 0;
00500 }
00501
00502