face_detection.cpp
Go to the documentation of this file.
00001 /**********************************************************************
00002  *
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2008, Willow Garage, Inc.
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/or other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the Willow Garage nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 
00036 /* Author: Caroline Pantofaru */
00037 
00038 
00039 
00040 #include <stdio.h>
00041 #include <iostream>
00042 #include <vector>
00043 #include <fstream>
00044 
00045 #include <ros/ros.h>
00046 #include <ros/console.h>
00047 #include <boost/filesystem.hpp>
00048 #include <boost/thread/mutex.hpp>
00049 
00050 #include <people_msgs/PositionMeasurement.h>
00051 #include <people_msgs/PositionMeasurementArray.h>
00052 #include <message_filters/subscriber.h>
00053 #include <message_filters/time_synchronizer.h>
00054 #include <message_filters/sync_policies/exact_time.h>
00055 #include <message_filters/sync_policies/approximate_time.h>
00056 #include <image_transport/subscriber_filter.h>
00057 #include "sensor_msgs/CameraInfo.h"
00058 #include "sensor_msgs/Image.h"
00059 #include "stereo_msgs/DisparityImage.h"
00060 #include "sensor_msgs/image_encodings.h"
00061 #include "cv_bridge/cv_bridge.h"
00062 #include "tf/transform_listener.h"
00063 #include "sensor_msgs/PointCloud.h"
00064 #include "geometry_msgs/Point32.h"
00065 
00066 #include "opencv/cxcore.hpp"
00067 #include "opencv/cv.hpp"
00068 #include "opencv/highgui.h"
00069 
00070 #include "face_detector/faces.h"
00071 
00072 #include "image_geometry/stereo_camera_model.h"
00073 
00074 #include <actionlib/server/simple_action_server.h>
00075 #include <face_detector/FaceDetectorAction.h>
00076 
00077 using namespace std;
00078 
00079 namespace people {
00080 
00083   class FaceDetector {
00084   public:
00085     // Constants
00086     const double BIGDIST_M;// = 1000000.0;
00087 
00088     // Node handle
00089     ros::NodeHandle nh_;
00090 
00091     boost::mutex connect_mutex_;
00092     bool use_rgbd_;
00093 
00094     // Subscription topics
00095     string image_topic_;
00096     // Stereo
00097     string stereo_namespace_;
00098     string left_topic_;
00099     string disparity_topic_;
00100     string left_camera_info_topic_;
00101     string right_camera_info_topic_;
00102     // RGB-D
00103     string camera_;
00104     string camera_topic_;
00105     string depth_topic_;
00106     string camera_info_topic_;
00107     string depth_info_topic_;
00108 
00109     // Images and conversion for both the stereo camera and rgb-d camera cases.
00110     image_transport::ImageTransport it_;
00111     image_transport::SubscriberFilter image_sub_; 
00112     image_transport::SubscriberFilter depth_image_sub_; 
00113     message_filters::Subscriber<stereo_msgs::DisparityImage> disp_image_sub_; 
00114     message_filters::Subscriber<sensor_msgs::CameraInfo> c1_info_sub_; 
00115     message_filters::Subscriber<sensor_msgs::CameraInfo> c2_info_sub_; 
00117     // Disparity:
00118     typedef message_filters::sync_policies::ExactTime<sensor_msgs::Image, stereo_msgs::DisparityImage, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo> ExactDispPolicy; 
00119     typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, stereo_msgs::DisparityImage, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo> ApproximateDispPolicy; 
00120     typedef message_filters::Synchronizer<ExactDispPolicy> ExactDispSync;
00121     typedef message_filters::Synchronizer<ApproximateDispPolicy> ApproximateDispSync;
00122     boost::shared_ptr<ExactDispSync> exact_disp_sync_;
00123     boost::shared_ptr<ApproximateDispSync> approximate_disp_sync_;
00124 
00125     // Depth:
00126     typedef message_filters::sync_policies::ExactTime<sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo> ExactDepthPolicy; 
00127     typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo> ApproximateDepthPolicy; 
00128     typedef message_filters::Synchronizer<ExactDepthPolicy> ExactDepthSync;
00129     typedef message_filters::Synchronizer<ApproximateDepthPolicy> ApproximateDepthSync;
00130     boost::shared_ptr<ExactDepthSync> exact_depth_sync_;
00131     boost::shared_ptr<ApproximateDepthSync> approximate_depth_sync_;
00132 
00133     // Action
00134     actionlib::SimpleActionServer<face_detector::FaceDetectorAction> as_;
00135     face_detector::FaceDetectorFeedback feedback_;
00136     face_detector::FaceDetectorResult result_;
00137 
00138     // If running the face detector as a component in part of a larger person tracker, this subscribes to the tracker's position measurements and whether it was initialized by some other node.
00139     // Todo: resurrect the person tracker.
00140     ros::Subscriber pos_sub_;
00141     bool external_init_;
00142 
00143 
00144     // Publishers
00145     // A point cloud of the face positions, meant for visualization in rviz.
00146     // This could be replaced by visualization markers, but they can't be modified
00147     // in rviz at runtime (eg the alpha, display time, etc. can't be changed.)
00148     ros::Publisher cloud_pub_;
00149     ros::Publisher pos_array_pub_;
00150 
00151     // Display
00152     bool do_display_; 
00153     cv::Mat cv_image_out_; 
00155     // Depth
00156     bool use_depth_; 
00157     image_geometry::StereoCameraModel cam_model_; 
00159     // Face detector params and output
00160     Faces *faces_; 
00161     string name_; 
00162     string haar_filename_; 
00163     double reliability_; 
00165     struct RestampedPositionMeasurement {
00166       ros::Time restamp;
00167       people_msgs::PositionMeasurement pos;
00168       double dist;
00169     };
00170     map<string, RestampedPositionMeasurement> pos_list_; 
00172     int max_id_;
00173 
00174     bool quit_;
00175 
00176     tf::TransformListener tf_;
00177 
00178     std::string fixed_frame_;
00179 
00180     boost::mutex cv_mutex_, pos_mutex_, limage_mutex_, dimage_mutex_;
00181 
00182     bool do_continuous_; 
00184     bool do_publish_unknown_; 
00186     FaceDetector(std::string name) :
00187       BIGDIST_M(1000000.0),
00188       it_(nh_),
00189       as_(nh_, name, false),
00190       faces_(0),
00191       max_id_(-1),
00192       quit_(false)
00193     {
00194       ROS_INFO_STREAM_NAMED("face_detector","Constructing FaceDetector.");
00195 
00196       // Action stuff
00197       as_.registerGoalCallback(boost::bind(&FaceDetector::goalCB, this));
00198       as_.registerPreemptCallback(boost::bind(&FaceDetector::preemptCB, this));
00199       as_.start();
00200 
00201       faces_ = new Faces();
00202       double face_size_min_m, face_size_max_m, max_face_z_m, face_sep_dist_m;
00203       int queue_size;
00204       bool approx;
00205 
00206       // Parameters
00207       ros::NodeHandle local_nh("~");
00208       local_nh.param("classifier_name",name_,std::string(""));
00209       local_nh.param("classifier_filename",haar_filename_,std::string(""));
00210       local_nh.param("classifier_reliability",reliability_,0.0);
00211       local_nh.param("do_display",do_display_,false);
00212       local_nh.param("do_continuous",do_continuous_,true);
00213       local_nh.param("do_publish_faces_of_unknown_size",do_publish_unknown_,false);
00214       local_nh.param("use_depth",use_depth_,true);
00215       local_nh.param("use_external_init",external_init_,false);
00216       local_nh.param("face_size_min_m",face_size_min_m,Faces::FACE_SIZE_MIN_M);
00217       local_nh.param("face_size_max_m",face_size_max_m,Faces::FACE_SIZE_MAX_M);
00218       local_nh.param("max_face_z_m",max_face_z_m,Faces::MAX_FACE_Z_M);
00219       local_nh.param("face_separation_dist_m",face_sep_dist_m,Faces::FACE_SEP_DIST_M);
00220       local_nh.param("use_rgbd",use_rgbd_,false);
00221       local_nh.param("queue_size", queue_size, 5);
00222       local_nh.param("approximate_sync", approx, false);
00223 
00224       if (do_display_) {
00225         // OpenCV: pop up an OpenCV highgui window
00226         cv::namedWindow("Face detector: Face Detection", CV_WINDOW_AUTOSIZE);
00227       }
00228 
00229       // Init the detector and subscribe to the images and camera parameters. One case for rgbd, one for stereo.
00230       if (use_rgbd_) {
00231 
00232         faces_->initFaceDetectionDepth(1, haar_filename_, face_size_min_m, face_size_max_m, max_face_z_m, face_sep_dist_m);
00233 
00234         camera_ = nh_.resolveName("camera");
00235         image_topic_ = nh_.resolveName("image");
00236         camera_topic_ = ros::names::clean(camera_ + "/rgb/" + image_topic_);
00237         depth_topic_ = ros::names::clean(camera_ + "/depth_registered/" + image_topic_);
00238         camera_info_topic_ = ros::names::clean(camera_ + "/rgb/camera_info");
00239         depth_info_topic_ = ros::names::clean(camera_ + "/depth_registered/camera_info");
00240 
00241         local_nh.param("fixed_frame", fixed_frame_, std::string("camera_rgb_optical_frame"));
00242 
00243         if (approx)
00244         {
00245           approximate_depth_sync_.reset( new ApproximateDepthSync(ApproximateDepthPolicy(queue_size),
00246                                                                   image_sub_, depth_image_sub_, c1_info_sub_, c2_info_sub_));
00247           approximate_depth_sync_->registerCallback(boost::bind(&FaceDetector::imageCBAllDepth,
00248                                                                 this, _1, _2, _3, _4));
00249         }
00250         else
00251         {
00252           exact_depth_sync_.reset( new ExactDepthSync(ExactDepthPolicy(queue_size),
00253                                                       image_sub_, depth_image_sub_, c1_info_sub_, c2_info_sub_));
00254           exact_depth_sync_->registerCallback(boost::bind(&FaceDetector::imageCBAllDepth,
00255                                                           this, _1, _2, _3, _4));
00256         }
00257 
00258       }
00259       else { 
00260         faces_->initFaceDetectionDisparity(1, haar_filename_, face_size_min_m, face_size_max_m, max_face_z_m, face_sep_dist_m);
00261 
00262         stereo_namespace_ = nh_.resolveName("camera");
00263         image_topic_ = nh_.resolveName("image");
00264         left_topic_ = ros::names::clean(stereo_namespace_ + "/left/" + image_topic_);
00265         disparity_topic_ = ros::names::clean(stereo_namespace_ + "/disparity");
00266         left_camera_info_topic_ = ros::names::clean(stereo_namespace_ + "/left/camera_info");
00267         right_camera_info_topic_ = ros::names::clean(stereo_namespace_ + "/right/camera_info");
00268 
00269         local_nh.param("fixed_frame", fixed_frame_, stereo_namespace_.append("_optical_frame"));
00270 
00271         if (approx)
00272         {
00273           approximate_disp_sync_.reset( new ApproximateDispSync(ApproximateDispPolicy(queue_size),
00274                                                                 image_sub_, disp_image_sub_, c1_info_sub_, c2_info_sub_));
00275           approximate_disp_sync_->registerCallback(boost::bind(&FaceDetector::imageCBAllDisp,
00276                                                                this, _1, _2, _3, _4));
00277         }
00278         else
00279         {
00280           exact_disp_sync_.reset( new ExactDispSync(ExactDispPolicy(queue_size),
00281                                                     image_sub_, disp_image_sub_, c1_info_sub_, c2_info_sub_));
00282           exact_disp_sync_->registerCallback(boost::bind(&FaceDetector::imageCBAllDisp,
00283                                                          this, _1, _2, _3, _4));
00284         }
00285       }
00286       
00287       // Connection callbacks and advertise
00288       ros::SubscriberStatusCallback pos_pub_connect_cb = boost::bind(&FaceDetector::connectCb, this);
00289       ros::SubscriberStatusCallback cloud_pub_connect_cb = boost::bind(&FaceDetector::connectCb, this);
00290 
00291       {
00292         boost::mutex::scoped_lock lock(connect_mutex_);
00293 
00294         // Advertise a position measure message.
00295         pos_array_pub_ = nh_.advertise<people_msgs::PositionMeasurementArray>("face_detector/people_tracker_measurements_array",1, pos_pub_connect_cb, pos_pub_connect_cb);
00296 
00297         cloud_pub_ = nh_.advertise<sensor_msgs::PointCloud>("face_detector/faces_cloud",0, cloud_pub_connect_cb, cloud_pub_connect_cb);
00298       }
00299 
00300 
00301       // If running as an action server, just stay connected so that action calls are fast.
00302       if (!do_continuous_) connectCb();
00303 
00304       ros::MultiThreadedSpinner s(2);
00305       ros::spin(s);
00306 
00307     }
00308 
00309     ~FaceDetector()
00310     {
00311 
00312       cv_image_out_.release();
00313 
00314       if (do_display_) {
00315         cv::destroyWindow("Face detector: Face Detection");
00316       }
00317 
00318       if (faces_) {delete faces_; faces_ = 0;}
00319     }
00320 
00321     // Handles (un)subscribing when clients (un)subscribe
00322     void connectCb()
00323     {
00324       boost::mutex::scoped_lock lock(connect_mutex_);
00325       if (use_rgbd_) 
00326       {
00327         if (do_continuous_ && cloud_pub_.getNumSubscribers() == 0 && pos_array_pub_.getNumSubscribers() == 0)
00328         {
00329           image_sub_.unsubscribe();
00330           depth_image_sub_.unsubscribe();
00331           c1_info_sub_.unsubscribe();
00332           c2_info_sub_.unsubscribe();
00333           pos_sub_.shutdown();
00334         }
00335         else if (!do_continuous_ || !image_sub_.getSubscriber())
00336         {
00337           image_sub_.subscribe(it_, camera_topic_, 3);
00338           depth_image_sub_.subscribe(it_, depth_topic_, 3);
00339           c1_info_sub_.subscribe(nh_, camera_info_topic_, 3);
00340           c2_info_sub_.subscribe(nh_, depth_info_topic_,3);   
00341           // // Subscribe to filter measurements.
00342           // if (external_init_) {
00343           //   //pos_sub_ = nh_.subscribe("people_tracker_filter",1,&FaceDetector::posCallback,this);
00344           //   pos_sub_ = nh_.subscribe("/face_detector/people_tracker_measurements_array",1,&FaceDetector::posCallback,this);
00345           // }
00346         }
00347       } 
00348       else
00349       {
00350         if (do_continuous_ && cloud_pub_.getNumSubscribers() == 0 && pos_array_pub_.getNumSubscribers() == 0)
00351         {
00352           image_sub_.unsubscribe();
00353           disp_image_sub_.unsubscribe();
00354           c1_info_sub_.unsubscribe();
00355           c2_info_sub_.unsubscribe();
00356           pos_sub_.shutdown();
00357         }
00358         else if (!do_continuous_ || !image_sub_.getSubscriber())
00359         {
00360           image_sub_.subscribe(it_, left_topic_, 3);
00361           disp_image_sub_.subscribe(nh_, disparity_topic_, 3);
00362           c1_info_sub_.subscribe(nh_, left_camera_info_topic_, 3);
00363           c2_info_sub_.subscribe(nh_, right_camera_info_topic_, 3);     
00364           // // Subscribe to filter measurements.
00365           // if (external_init_) {
00366           //   //pos_sub_ = nh_.subscribe("people_tracker_filter",1,&FaceDetector::posCallback,this);
00367           //   pos_sub_ = nh_.subscribe("/face_detector/people_tracker_measurements_array",1,&FaceDetector::posCallback,this);
00368           // }
00369         }
00370       }
00371     }
00372 
00373 
00374     void goalCB() {
00375       as_.acceptNewGoal();
00376     }
00377 
00378     void preemptCB() {
00379       as_.setPreempted();
00380     }
00381 
00382 
00389     // void posCallback(const people_msgs::PositionMeasurementArrayConstPtr& pos_array_ptr) {
00390 
00391     //   // Put the incoming position into the position queue. It'll be processed in the next image callback.
00392     //   boost::mutex::scoped_lock lock(pos_mutex_);
00393 
00394     //   map<string, RestampedPositionMeasurement>::iterator it;
00395     //   for (uint ipa = 0; ipa < pos_array_ptr->people.size(); ipa++) {
00396     //     it = pos_list_.find(pos_array_ptr->people[ipa].object_id);
00397     //     RestampedPositionMeasurement rpm;
00398     //     rpm.pos = pos_array_ptr->people[ipa];
00399     //     rpm.restamp = pos_array_ptr->people[ipa].header.stamp;
00400     //     rpm.dist = BIGDIST_M;
00401     //     if (it == pos_list_.end()) {
00402     //  pos_list_.insert(pair<string, RestampedPositionMeasurement>(pos_array_ptr->people[ipa].object_id, rpm));
00403     //     }
00404     //     else if ((pos_array_ptr->people[ipa].header.stamp - (*it).second.pos.header.stamp) > ros::Duration().fromSec(-1.0) ){
00405     //  (*it).second = rpm;
00406     //     }
00407     //   }
00408     //   lock.unlock();
00409 
00410     // }
00411 
00412     // Workaround to convert a DisparityImage->Image into a shared pointer for cv_bridge in imageCBAll.
00413     struct NullDeleter
00414     {
00415       void operator()(void const *) const {}
00416     };
00417 
00426     void imageCBAllDepth(const sensor_msgs::Image::ConstPtr &image, const sensor_msgs::Image::ConstPtr& depth_image, const sensor_msgs::CameraInfo::ConstPtr& c1_info, const sensor_msgs::CameraInfo::ConstPtr& c2_info)
00427     {
00428 
00429       // Only run the detector if in continuous mode or the detector was turned on through an action invocation.
00430       if (!do_continuous_ && !as_.isActive())
00431         return; 
00432 
00433       // Clear out the result vector.
00434       result_.face_positions.clear();
00435 
00436       if (do_display_) {
00437         cv_mutex_.lock();
00438       }
00439 
00440       // ROS --> OpenCV
00441       cv_bridge::CvImageConstPtr cv_image_ptr = cv_bridge::toCvShare(image,"bgr8");
00442       cv_bridge::CvImageConstPtr cv_depth_ptr = cv_bridge::toCvShare(depth_image);
00443       cam_model_.fromCameraInfo(c1_info,c2_info);
00444 
00445       // For display, keep a copy of the image that we can draw on.
00446       if (do_display_) {
00447         cv_image_out_ = (cv_image_ptr->image).clone();
00448       }
00449 
00450       struct timeval timeofday;
00451       gettimeofday(&timeofday,NULL);
00452       ros::Time starttdetect = ros::Time().fromNSec(1e9*timeofday.tv_sec + 1e3*timeofday.tv_usec);
00453 
00454       vector<Box2D3D> faces_vector = faces_->detectAllFacesDepth(cv_image_ptr->image, 1.0, cv_depth_ptr->image, &cam_model_);
00455       gettimeofday(&timeofday,NULL);
00456       ros::Time endtdetect = ros::Time().fromNSec(1e9*timeofday.tv_sec + 1e3*timeofday.tv_usec);
00457       ros::Duration diffdetect = endtdetect - starttdetect;
00458       ROS_INFO_STREAM_NAMED("face_detector","Detection duration = " << diffdetect.toSec() << "sec");
00459 
00460       matchAndDisplay(faces_vector, image->header);
00461     }
00462 
00471     void imageCBAllDisp(const sensor_msgs::Image::ConstPtr &image, const stereo_msgs::DisparityImage::ConstPtr& disp_image, const sensor_msgs::CameraInfo::ConstPtr& c1_info, const sensor_msgs::CameraInfo::ConstPtr& c2_info)
00472     {
00473 
00474       // Only run the detector if in continuous mode or the detector was turned on through an action invocation.
00475       if (!do_continuous_ && !as_.isActive())
00476         return;
00477 
00478       // Clear out the result vector.
00479       result_.face_positions.clear();
00480 
00481       if (do_display_) {
00482         cv_mutex_.lock();
00483       }
00484 
00485 
00486       // ROS --> OpenCV
00487       cv_bridge::CvImageConstPtr cv_image_ptr = cv_bridge::toCvShare(image,sensor_msgs::image_encodings::BGR8);
00488       cv_bridge::CvImageConstPtr cv_disp_ptr = cv_bridge::toCvShare(disp_image->image, disp_image);
00489       cam_model_.fromCameraInfo(c1_info,c2_info);
00490 
00491       // For display, keep a copy of the image that we can draw on.
00492       if (do_display_) {
00493         cv_image_out_ = (cv_image_ptr->image).clone();
00494       }
00495 
00496       struct timeval timeofday;
00497       gettimeofday(&timeofday,NULL);
00498       ros::Time starttdetect = ros::Time().fromNSec(1e9*timeofday.tv_sec + 1e3*timeofday.tv_usec);
00499 
00500       vector<Box2D3D> faces_vector = faces_->detectAllFacesDisparity(cv_image_ptr->image, 1.0, cv_disp_ptr->image, &cam_model_);
00501       gettimeofday(&timeofday,NULL);
00502       ros::Time endtdetect = ros::Time().fromNSec(1e9*timeofday.tv_sec + 1e3*timeofday.tv_usec);
00503       ros::Duration diffdetect = endtdetect - starttdetect;
00504       ROS_INFO_STREAM_NAMED("face_detector","Detection duration = " << diffdetect.toSec() << "sec");
00505 
00506       matchAndDisplay(faces_vector, image->header);
00507     }
00508 
00509 
00510   private:
00511 
00512     void matchAndDisplay( vector<Box2D3D> faces_vector, std_msgs::Header header ) 
00513     {
00514       bool found_faces = false;
00515 
00516       int ngood = 0;
00517       sensor_msgs::PointCloud cloud;
00518       cloud.header.stamp = header.stamp;
00519       cloud.header.frame_id = header.frame_id;
00520 
00521       if (faces_vector.size() > 0 ) {
00522 
00523         // Transform the positions of the known faces and remove anyone who hasn't had an update in a long time.
00524         //      boost::mutex::scoped_lock pos_lock(pos_mutex_);
00525         map<string, RestampedPositionMeasurement>::iterator it;
00526         it = pos_list_.begin();
00527         while (it != pos_list_.end()) {
00528           if ((header.stamp - (*it).second.restamp) > ros::Duration().fromSec(5.0)) {
00529             // Position is too old, remove the person.
00530             pos_list_.erase(it++);
00531           }
00532           else {
00533             // Transform the person to this time. Note that the pos time is updated but not the restamp.
00534             tf::Point pt;
00535             tf::pointMsgToTF((*it).second.pos.pos, pt);
00536             tf::Stamped<tf::Point> loc(pt, (*it).second.pos.header.stamp, (*it).second.pos.header.frame_id);
00537             try {
00538               tf_.transformPoint(header.frame_id, header.stamp, loc, fixed_frame_, loc);
00539               (*it).second.pos.header.stamp = header.stamp;
00540               (*it).second.pos.pos.x = loc[0];
00541               (*it).second.pos.pos.y = loc[1];
00542               (*it).second.pos.pos.z = loc[2];
00543             }
00544             catch (tf::TransformException& ex) {
00545             }
00546             it++;
00547           }
00548         }
00549         // End filter face position update
00550 
00551         // Associate the found faces with previously seen faces, and publish all good face centers.
00552         Box2D3D *one_face;
00553         people_msgs::PositionMeasurement pos;
00554         people_msgs::PositionMeasurementArray pos_array;
00555 
00556         for (uint iface = 0; iface < faces_vector.size(); iface++) {
00557           one_face = &faces_vector[iface];
00558 
00559           if (one_face->status=="good" || (one_face->status=="unknown" && do_publish_unknown_)) {
00560 
00561             std::string id = "";
00562 
00563             // Convert the face format to a PositionMeasurement msg.
00564             pos.header.stamp = header.stamp;
00565             pos.name = name_;
00566             pos.pos.x = one_face->center3d.x;
00567             pos.pos.y = one_face->center3d.y;
00568             pos.pos.z = one_face->center3d.z;
00569             pos.header.frame_id = header.frame_id;//"*_optical_frame";
00570             pos.reliability = reliability_;
00571             pos.initialization = 1;//0;
00572             pos.covariance[0] = 0.04; pos.covariance[1] = 0.0;  pos.covariance[2] = 0.0;
00573             pos.covariance[3] = 0.0;  pos.covariance[4] = 0.04; pos.covariance[5] = 0.0;
00574             pos.covariance[6] = 0.0;  pos.covariance[7] = 0.0;  pos.covariance[8] = 0.04;
00575 
00576             // Check if this person's face is close enough to one of the previously known faces and associate it with the closest one.
00577             // Otherwise publish it with an empty id.
00578             // Note that multiple face positions can be published with the same id, but ids in the pos_list_ are unique. The position of a face in the list is updated with the closest found face.
00579             double dist, mindist = BIGDIST_M;
00580             map<string, RestampedPositionMeasurement>::iterator close_it = pos_list_.end();
00581             for (it = pos_list_.begin(); it != pos_list_.end(); it++) {
00582               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);
00583               if (dist <= faces_->face_sep_dist_m_ && dist < mindist) {
00584                 mindist = dist;
00585                 close_it = it;
00586               }
00587             }
00588             if (close_it != pos_list_.end()) {
00589               pos.object_id = (*close_it).second.pos.object_id;
00590               if (mindist < (*close_it).second.dist) {
00591                 (*close_it).second.restamp = header.stamp;
00592                 (*close_it).second.dist = mindist;
00593                 (*close_it).second.pos = pos;
00594               }
00595               ROS_INFO_STREAM_NAMED("face_detector","Found face to match with id " << pos.object_id);
00596             }
00597             else {
00598               max_id_++;
00599               pos.object_id = static_cast<ostringstream*>( &(ostringstream() << max_id_) )->str();
00600               ROS_INFO_STREAM_NAMED("face_detector","Didn't find face to match, starting new ID " << pos.object_id);
00601             }
00602             result_.face_positions.push_back(pos);
00603             found_faces = true;
00604 
00605           }
00606 
00607         }
00608         pos_array.header.stamp = header.stamp;
00609         pos_array.header.frame_id = header.frame_id;
00610         pos_array.people = result_.face_positions;
00611         if (pos_array.people.size() > 0) {
00612           pos_array_pub_.publish(pos_array);
00613 
00614           // Update the position list greedily. This should be rewritten.
00615           map<string, RestampedPositionMeasurement>::iterator it;
00616           for (uint ipa = 0; ipa < pos_array.people.size(); ipa++) {
00617             it = pos_list_.find(pos_array.people[ipa].object_id);
00618             RestampedPositionMeasurement rpm;
00619             rpm.pos = pos_array.people[ipa];
00620             rpm.restamp = pos_array.people[ipa].header.stamp;
00621             rpm.dist = BIGDIST_M;
00622             if (it == pos_list_.end()) {
00623               pos_list_.insert(pair<string, RestampedPositionMeasurement>(pos_array.people[ipa].object_id, rpm));
00624             }
00625             else if ((pos_array.people[ipa].header.stamp - (*it).second.pos.header.stamp) > ros::Duration().fromSec(-1.0) ){
00626               (*it).second = rpm;
00627             }
00628           }
00629           //      pos_lock.unlock();
00630 
00631           // Clean out all of the distances in the pos_list_
00632           for (it = pos_list_.begin(); it != pos_list_.end(); it++) {
00633             (*it).second.dist = BIGDIST_M;
00634           }
00635 
00636         }
00637 
00638 
00639         // Done associating faces
00640 
00641         /******** Display **************************************************************/
00642 
00643         // Publish a point cloud of face centers.
00644 
00645         cloud.channels.resize(1);
00646         cloud.channels[0].name = "intensity";
00647 
00648         for (uint iface = 0; iface < faces_vector.size(); iface++) {
00649           one_face = &faces_vector[iface];
00650 
00651           // Visualization of good faces as a point cloud
00652           if (one_face->status == "good") {
00653 
00654             geometry_msgs::Point32 p;
00655             p.x = one_face->center3d.x;
00656             p.y = one_face->center3d.y;
00657             p.z = one_face->center3d.z;
00658             cloud.points.push_back(p);
00659             cloud.channels[0].values.push_back(1.0f);
00660 
00661             ngood ++;
00662           }
00663         }
00664 
00665         cloud_pub_.publish(cloud);
00666         // Done publishing the point cloud.
00667 
00668       } // Done if faces_vector.size() > 0
00669     
00670 
00671       // Draw an appropriately colored rectangle on the display image and in the visualizer.
00672       if (do_display_) {
00673         displayFacesOnImage(faces_vector);
00674         cv_mutex_.unlock();
00675       }
00676       // Done drawing.
00677 
00678       /******** Done display **********************************************************/
00679 
00680       ROS_INFO_STREAM_NAMED("face_detector","Number of faces found: " << faces_vector.size() << ", number with good depth and size: " << ngood);
00681 
00682       // If you don't want continuous processing and you've found at least one face, turn off the detector.
00683       if (!do_continuous_ && found_faces) {
00684         as_.setSucceeded(result_);
00685       }
00686     }
00687 
00688     // Draw bounding boxes around detected faces on the cv_image_out_ and show the image. 
00689     void displayFacesOnImage(vector<Box2D3D>  faces_vector) 
00690     {
00691 
00692       Box2D3D *one_face;
00693     
00694       for (uint iface = 0; iface < faces_vector.size(); iface++) {
00695         one_face = &faces_vector[iface];
00696         // Visualization by image display.
00697         if (do_display_) {
00698           cv::Scalar color;
00699           if (one_face->status == "good") {
00700             color = cv::Scalar(0,255,0);
00701           }
00702           else if (one_face->status == "unknown") {
00703             color = cv::Scalar(255,0,0);
00704           }
00705           else {
00706             color = cv::Scalar(0,0,255);
00707           }
00708         
00709           cv::rectangle(cv_image_out_, 
00710                         cv::Point(one_face->box2d.x,one_face->box2d.y), 
00711                         cv::Point(one_face->box2d.x+one_face->box2d.width, one_face->box2d.y+one_face->box2d.height), color, 4);
00712         }
00713       }
00714 
00715       cv::imshow("Face detector: Face Detection",cv_image_out_);
00716       cv::waitKey(2);
00717     
00718     }
00719 
00720 
00721   }; // end class
00722 
00723 }; // end namespace people
00724 
00725 // Main
00726 int main(int argc, char **argv)
00727 {
00728   ros::init(argc,argv,"face_detector");
00729 
00730   people::FaceDetector fd(ros::this_node::getName());
00731 
00732   return 0;
00733 }
00734 
00735 


face_detector
Author(s): Caroline Pantofaru
autogenerated on Mon Oct 6 2014 03:17:09