face_detection.cpp
Go to the documentation of this file.
1 /**********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2008, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of the Willow Garage nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 /* Author: Caroline Pantofaru */
37 
38 #include <stdio.h>
39 #include <iostream>
40 #include <vector>
41 #include <fstream>
42 #include <map>
43 #include <string>
44 #include <utility>
45 
46 #include <ros/ros.h>
47 #include <ros/console.h>
48 #include <boost/filesystem.hpp>
49 #include <boost/thread/mutex.hpp>
50 
51 #include <people_msgs/PositionMeasurement.h>
52 #include <people_msgs/PositionMeasurementArray.h>
58 #include <sensor_msgs/CameraInfo.h>
59 #include <sensor_msgs/Image.h>
60 #include <stereo_msgs/DisparityImage.h>
62 #include <cv_bridge/cv_bridge.h>
63 #include <tf/transform_listener.h>
64 #include <sensor_msgs/PointCloud.h>
65 #include <geometry_msgs/Point32.h>
66 
67 #include <opencv/cxcore.hpp>
68 #include <opencv/cv.hpp>
69 #include <opencv/highgui.h>
70 
71 #include <face_detector/faces.h>
72 
74 
76 #include <face_detector/FaceDetectorAction.h>
77 
78 namespace people
79 {
80 
84 {
85 public:
86  // Constants
87  const double BIGDIST_M; // = 1000000.0;
88 
89  // Node handle
91 
92  boost::mutex connect_mutex_;
93  bool use_rgbd_;
94 
95  // Subscription topics
96  std::string image_image_;
97  // Stereo
98  std::string stereo_namespace_;
99  std::string left_topic_;
100  std::string disparity_topic_;
103  // RGB-D
104  std::string camera_;
105  std::string camera_topic_;
106  std::string depth_image_;
107  std::string depth_topic_;
108  std::string camera_info_topic_;
109  std::string depth_info_topic_;
110  std::string rgb_ns_;
111  std::string depth_ns_;
112 
113  // Images and conversion for both the stereo camera and rgb-d camera cases.
121  // Disparity:
123  <sensor_msgs::Image, stereo_msgs::DisparityImage, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo>
126  <sensor_msgs::Image, stereo_msgs::DisparityImage, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo>
132 
133  // Depth:
135  <sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo>
138  <sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo>
144 
145  // Action
147  face_detector::FaceDetectorFeedback feedback_;
148  face_detector::FaceDetectorResult result_;
149 
150  // If running the face detector as a component in part of a larger person tracker,
151  // this subscribes to the tracker's position measurements and whether it was initialized by some other node.
152  // Todo: resurrect the person tracker.
155 
156  // Publishers
157  // A point cloud of the face positions, meant for visualization in rviz.
158  // This could be replaced by visualization markers, but they can't be modified
159  // in rviz at runtime (eg the alpha, display time, etc. can't be changed.)
162 
163  // Display
164  bool do_display_;
165  cv::Mat cv_image_out_;
167  // Depth
168  bool use_depth_;
171  // Face detector params and output
173  std::string name_;
174  std::string haar_filename_;
175  double reliability_;
178  {
180  people_msgs::PositionMeasurement pos;
181  double dist;
182  };
183  std::map<std::string, RestampedPositionMeasurement> pos_list_;
185  int max_id_;
186 
187  bool quit_;
188 
190 
191  std::string fixed_frame_;
192 
194 
198  // Will just use the image x, y in the pos field of the published position_measurement.
199 
200  explicit FaceDetector(std::string name) :
201  BIGDIST_M(1000000.0),
202  it_(nh_),
203  as_(nh_, name, false),
204  faces_(0),
205  max_id_(-1),
206  quit_(false)
207  {
208  ROS_INFO_STREAM_NAMED("face_detector", "Constructing FaceDetector.");
209 
210  // Action stuff
211  as_.registerGoalCallback(boost::bind(&FaceDetector::goalCB, this));
212  as_.registerPreemptCallback(boost::bind(&FaceDetector::preemptCB, this));
213  as_.start();
214 
215  faces_ = new Faces();
216  double face_size_min_m, face_size_max_m, max_face_z_m, face_sep_dist_m;
217  int queue_size;
218  bool approx;
219 
220  // Parameters
221  ros::NodeHandle local_nh("~");
222  local_nh.param("classifier_name", name_, std::string(""));
223  local_nh.param("classifier_filename", haar_filename_, std::string(""));
224  local_nh.param("classifier_reliability", reliability_, 0.0);
225  local_nh.param("do_display", do_display_, false);
226  local_nh.param("do_continuous", do_continuous_, true);
227  local_nh.param("do_publish_faces_of_unknown_size", do_publish_unknown_, false);
228  local_nh.param("use_depth", use_depth_, true);
229  local_nh.param("use_external_init", external_init_, false);
230  local_nh.param("face_size_min_m", face_size_min_m, FACE_SIZE_MIN_M);
231  local_nh.param("face_size_max_m", face_size_max_m, FACE_SIZE_MAX_M);
232  local_nh.param("max_face_z_m", max_face_z_m, MAX_FACE_Z_M);
233  local_nh.param("face_separation_dist_m", face_sep_dist_m, FACE_SEP_DIST_M);
234  local_nh.param("use_rgbd", use_rgbd_, false);
235  local_nh.param("queue_size", queue_size, 5);
236  local_nh.param("approximate_sync", approx, false);
237 
238  if (do_display_)
239  {
240  // OpenCV: pop up an OpenCV highgui window
241  cv::namedWindow("Face detector: Face Detection", CV_WINDOW_AUTOSIZE);
242  }
243 
244  // Init the detector and subscribe to the images and camera parameters. One case for rgbd, one for stereo.
245  if (use_rgbd_)
246  {
247  faces_->initFaceDetectionDepth(1, haar_filename_,
248  face_size_min_m, face_size_max_m, max_face_z_m, face_sep_dist_m);
249 
250  camera_ = nh_.resolveName("camera");
251  image_image_ = nh_.resolveName("image_topic");
252  depth_image_ = nh_.resolveName("depth_topic");
253  rgb_ns_ = nh_.resolveName("rgb_ns");
254  depth_ns_ = nh_.resolveName("depth_ns");
255  camera_topic_ = ros::names::clean(camera_ + "/" + rgb_ns_ + "/" + image_image_);
256  depth_topic_ = ros::names::clean(camera_ + "/" + depth_ns_ + "/" + depth_image_);
257  camera_info_topic_ = ros::names::clean(camera_ + "/" + rgb_ns_ + "/camera_info");
258  depth_info_topic_ = ros::names::clean(camera_ + "/" + depth_ns_ + "/camera_info");
259 
260  ROS_DEBUG("camera_topic_: %s", camera_topic_.c_str());
261  ROS_DEBUG("depth_topic_: %s", depth_topic_.c_str());
262  ROS_DEBUG("camera_info_topic_: %s", camera_info_topic_.c_str());
263  ROS_DEBUG("depth_info_topic_: %s", depth_info_topic_.c_str());
264 
265  local_nh.param("fixed_frame", fixed_frame_, std::string("camera_rgb_optical_frame"));
266 
267  if (approx)
268  {
269  approximate_depth_sync_.reset(new ApproximateDepthSync(ApproximateDepthPolicy(queue_size),
270  image_sub_, depth_image_sub_, c1_info_sub_, c2_info_sub_));
271  approximate_depth_sync_->registerCallback(boost::bind(&FaceDetector::imageCBAllDepth,
272  this, _1, _2, _3, _4));
273  }
274  else
275  {
276  exact_depth_sync_.reset(new ExactDepthSync(ExactDepthPolicy(queue_size),
277  image_sub_, depth_image_sub_, c1_info_sub_, c2_info_sub_));
278  exact_depth_sync_->registerCallback(boost::bind(&FaceDetector::imageCBAllDepth,
279  this, _1, _2, _3, _4));
280  }
281  }
282  else
283  {
284  faces_->initFaceDetectionDisparity(1, haar_filename_,
285  face_size_min_m, face_size_max_m, max_face_z_m, face_sep_dist_m);
286 
287  stereo_namespace_ = nh_.resolveName("camera");
288  image_image_ = nh_.resolveName("image_topic");
289  left_topic_ = ros::names::clean(stereo_namespace_ + "/left/" + image_image_);
290  disparity_topic_ = ros::names::clean(stereo_namespace_ + "/disparity");
291  left_camera_info_topic_ = ros::names::clean(stereo_namespace_ + "/left/camera_info");
292  right_camera_info_topic_ = ros::names::clean(stereo_namespace_ + "/right/camera_info");
293 
294  local_nh.param("fixed_frame", fixed_frame_, stereo_namespace_.append("_optical_frame"));
295 
296  if (approx)
297  {
298  approximate_disp_sync_.reset(new ApproximateDispSync(ApproximateDispPolicy(queue_size),
299  image_sub_, disp_image_sub_, c1_info_sub_, c2_info_sub_));
300  approximate_disp_sync_->registerCallback(boost::bind(&FaceDetector::imageCBAllDisp,
301  this, _1, _2, _3, _4));
302  }
303  else
304  {
305  exact_disp_sync_.reset(new ExactDispSync(ExactDispPolicy(queue_size),
306  image_sub_, disp_image_sub_, c1_info_sub_, c2_info_sub_));
307  exact_disp_sync_->registerCallback(boost::bind(&FaceDetector::imageCBAllDisp,
308  this, _1, _2, _3, _4));
309  }
310  }
311 
312  // Connection callbacks and advertise
313  ros::SubscriberStatusCallback pos_pub_connect_cb = boost::bind(&FaceDetector::connectCb, this);
314  ros::SubscriberStatusCallback cloud_pub_connect_cb = boost::bind(&FaceDetector::connectCb, this);
315  if (do_continuous_)
316  ROS_INFO_STREAM_NAMED("face_detector", "You must subscribe to one of FaceDetector's outbound topics "
317  "or else it will not publish anything.");
318 
319  {
320  boost::mutex::scoped_lock lock(connect_mutex_);
321 
322  // Advertise a position measure message.
323  pos_array_pub_ = nh_.advertise<people_msgs::PositionMeasurementArray>(
324  "face_detector/people_tracker_measurements_array", 1, pos_pub_connect_cb, pos_pub_connect_cb);
325 
326  cloud_pub_ = nh_.advertise<sensor_msgs::PointCloud>("face_detector/faces_cloud", 0,
327  cloud_pub_connect_cb, cloud_pub_connect_cb);
328  }
329 
330  // If running as an action server, just stay connected so that action calls are fast.
331  if (!do_continuous_) connectCb();
332 
334  ros::spin(s);
335  }
336 
338  {
339  cv_image_out_.release();
340 
341  if (do_display_)
342  {
343  cv::destroyWindow("Face detector: Face Detection");
344  }
345 
346  if (faces_)
347  {
348  delete faces_;
349  faces_ = 0;
350  }
351  }
352 
353  // Handles (un)subscribing when clients (un)subscribe
354  void connectCb()
355  {
356  boost::mutex::scoped_lock lock(connect_mutex_);
357  if (use_rgbd_)
358  {
359  if (do_continuous_ && cloud_pub_.getNumSubscribers() == 0 && pos_array_pub_.getNumSubscribers() == 0)
360  {
361  ROS_INFO_STREAM_NAMED("face_detector", "You have unsubscribed to FaceDetector's outbound topics, "
362  "so it will no longer publish anything.");
363  image_sub_.unsubscribe();
364  depth_image_sub_.unsubscribe();
365  c1_info_sub_.unsubscribe();
366  c2_info_sub_.unsubscribe();
367  pos_sub_.shutdown();
368  }
369  else if (!do_continuous_ || !image_sub_.getSubscriber())
370  {
371  image_sub_.subscribe(it_, camera_topic_, 3);
372  depth_image_sub_.subscribe(it_, depth_topic_, 3);
373  c1_info_sub_.subscribe(nh_, camera_info_topic_, 3);
374  c2_info_sub_.subscribe(nh_, depth_info_topic_, 3);
375  // // Subscribe to filter measurements.
376  // if (external_init_) {
377  // //pos_sub_ = nh_.subscribe("people_tracker_filter",1,&FaceDetector::posCallback,this);
378  // pos_sub_ = nh_.subscribe("/face_detector/people_tracker_measurements_array",
379  // 1,&FaceDetector::posCallback,this);
380  // }
381  }
382  }
383  else
384  {
385  if (do_continuous_ && cloud_pub_.getNumSubscribers() == 0 && pos_array_pub_.getNumSubscribers() == 0)
386  {
387  ROS_INFO_STREAM_NAMED("face_detector", "You have unsubscribed to FaceDetector's outbound topics, "
388  "so it will no longer publish anything.");
389  image_sub_.unsubscribe();
390  disp_image_sub_.unsubscribe();
391  c1_info_sub_.unsubscribe();
392  c2_info_sub_.unsubscribe();
393  pos_sub_.shutdown();
394  }
395  else if (!do_continuous_ || !image_sub_.getSubscriber())
396  {
397  image_sub_.subscribe(it_, left_topic_, 3);
398  disp_image_sub_.subscribe(nh_, disparity_topic_, 3);
399  c1_info_sub_.subscribe(nh_, left_camera_info_topic_, 3);
400  c2_info_sub_.subscribe(nh_, right_camera_info_topic_, 3);
401  // // Subscribe to filter measurements.
402  // if (external_init_) {
403  // //pos_sub_ = nh_.subscribe("people_tracker_filter",1,&FaceDetector::posCallback,this);
404  // pos_sub_ = nh_.subscribe("/face_detector/people_tracker_measurements_array",1,
405  // &FaceDetector::posCallback,this);
406  // }
407  }
408  }
409  }
410 
411  void goalCB()
412  {
413  as_.acceptNewGoal();
414  }
415 
416  void preemptCB()
417  {
418  as_.setPreempted();
419  }
420 
427  // void posCallback(const people_msgs::PositionMeasurementArrayConstPtr& pos_array_ptr) {
428 
429  // // Put the incoming position into the position queue. It'll be processed in the next image callback.
430  // boost::mutex::scoped_lock lock(pos_mutex_);
431 
432  // std::map<std::string, RestampedPositionMeasurement>::iterator it;
433  // for (uint ipa = 0; ipa < pos_array_ptr->people.size(); ipa++) {
434  // it = pos_list_.find(pos_array_ptr->people[ipa].object_id);
435  // RestampedPositionMeasurement rpm;
436  // rpm.pos = pos_array_ptr->people[ipa];
437  // rpm.restamp = pos_array_ptr->people[ipa].header.stamp;
438  // rpm.dist = BIGDIST_M;
439  // if (it == pos_list_.end()) {
440  // pos_list_.insert(pair<std::string, RestampedPositionMeasurement>(pos_array_ptr->people[ipa].object_id, rpm));
441  // }
442  // else if ((pos_array_ptr->people[ipa].header.stamp - (*it).second.pos.header.stamp) >
443  // ros::Duration().fromSec(-1.0) ){
444  // (*it).second = rpm;
445  // }
446  // }
447  // lock.unlock();
448 
449  // }
450 
451  // Workaround to convert a DisparityImage->Image into a shared pointer for cv_bridge in imageCBAll.
452  struct NullDeleter
453  {
454  void operator()(void const *) const {}
455  };
456 
466  void imageCBAllDepth(const sensor_msgs::Image::ConstPtr &image,
467  const sensor_msgs::Image::ConstPtr& depth_image,
468  const sensor_msgs::CameraInfo::ConstPtr& c1_info,
469  const sensor_msgs::CameraInfo::ConstPtr& c2_info)
470  {
471  // Only run the detector if in continuous mode or the detector was turned on through an action invocation.
472  if (!do_continuous_ && !as_.isActive())
473  return;
474 
475  // Clear out the result vector.
476  result_.face_positions.clear();
477 
478  if (do_display_)
479  {
480  cv_mutex_.lock();
481  }
482 
483  // ROS --> OpenCV
484  cv_bridge::CvImageConstPtr cv_image_ptr = cv_bridge::toCvShare(image, "bgr8");
485  cv_bridge::CvImageConstPtr cv_depth_ptr = cv_bridge::toCvShare(depth_image);
486  cv::Mat depth_32fc1 = cv_depth_ptr->image;
487  if (depth_image->encoding != "32FC1")
488  {
489  cv_depth_ptr->image.convertTo(depth_32fc1, CV_32FC1, 0.001);
490  }
491 
492  cam_model_.fromCameraInfo(c1_info, c2_info);
493 
494  // For display, keep a copy of the image that we can draw on.
495  if (do_display_)
496  {
497  cv_image_out_ = (cv_image_ptr->image).clone();
498  }
499 
500  struct timeval timeofday;
501  gettimeofday(&timeofday, NULL);
502  ros::Time starttdetect = ros::Time().fromNSec(1e9 * timeofday.tv_sec + 1e3 * timeofday.tv_usec);
503 
504  std::vector<Box2D3D> faces_vector = faces_->detectAllFacesDepth(cv_image_ptr->image, 1.0, depth_32fc1, &cam_model_);
505  gettimeofday(&timeofday, NULL);
506  ros::Time endtdetect = ros::Time().fromNSec(1e9 * timeofday.tv_sec + 1e3 * timeofday.tv_usec);
507  ros::Duration diffdetect = endtdetect - starttdetect;
508  ROS_INFO_STREAM_NAMED("face_detector", "Detection duration = " << diffdetect.toSec() << "sec");
509 
510  matchAndDisplay(faces_vector, image->header);
511  }
512 
521  void imageCBAllDisp(const sensor_msgs::Image::ConstPtr &image,
522  const stereo_msgs::DisparityImage::ConstPtr& disp_image,
523  const sensor_msgs::CameraInfo::ConstPtr& c1_info,
524  const sensor_msgs::CameraInfo::ConstPtr& c2_info)
525  {
526  // Only run the detector if in continuous mode or the detector was turned on through an action invocation.
527  if (!do_continuous_ && !as_.isActive())
528  return;
529 
530  // Clear out the result vector.
531  result_.face_positions.clear();
532 
533  if (do_display_)
534  {
535  cv_mutex_.lock();
536  }
537 
538  // ROS --> OpenCV
540  cv_bridge::CvImageConstPtr cv_disp_ptr = cv_bridge::toCvShare(disp_image->image, disp_image);
541  cam_model_.fromCameraInfo(c1_info, c2_info);
542 
543  // For display, keep a copy of the image that we can draw on.
544  if (do_display_)
545  {
546  cv_image_out_ = (cv_image_ptr->image).clone();
547  }
548 
549  struct timeval timeofday;
550  gettimeofday(&timeofday, NULL);
551  ros::Time starttdetect = ros::Time().fromNSec(1e9 * timeofday.tv_sec + 1e3 * timeofday.tv_usec);
552 
553  std::vector<Box2D3D> faces_vector = faces_->detectAllFacesDisparity(cv_image_ptr->image, 1.0,
554  cv_disp_ptr->image, &cam_model_);
555  gettimeofday(&timeofday, NULL);
556  ros::Time endtdetect = ros::Time().fromNSec(1e9 * timeofday.tv_sec + 1e3 * timeofday.tv_usec);
557  ros::Duration diffdetect = endtdetect - starttdetect;
558  ROS_INFO_STREAM_NAMED("face_detector", "Detection duration = " << diffdetect.toSec() << "sec");
559 
560  matchAndDisplay(faces_vector, image->header);
561  }
562 
563 private:
564  void matchAndDisplay(std::vector<Box2D3D> faces_vector, std_msgs::Header header)
565  {
566  bool found_faces = false;
567 
568  int ngood = 0;
569  sensor_msgs::PointCloud cloud;
570  cloud.header.stamp = header.stamp;
571  cloud.header.frame_id = header.frame_id;
572 
573  if (faces_vector.size() > 0)
574  {
575  // Transform the positions of the known faces and remove anyone who hasn't had an update in a long time.
576  // boost::mutex::scoped_lock pos_lock(pos_mutex_);
577  std::map<std::string, RestampedPositionMeasurement>::iterator it;
578  it = pos_list_.begin();
579  while (it != pos_list_.end())
580  {
581  if ((header.stamp - (*it).second.restamp) > ros::Duration().fromSec(5.0))
582  {
583  // Position is too old, remove the person.
584  pos_list_.erase(it++);
585  }
586  else
587  {
588  // Transform the person to this time. Note that the pos time is updated but not the restamp.
589  tf::Point pt;
590  tf::pointMsgToTF((*it).second.pos.pos, pt);
591  tf::Stamped<tf::Point> loc(pt, (*it).second.pos.header.stamp, (*it).second.pos.header.frame_id);
592  try
593  {
594  tf_.transformPoint(header.frame_id, header.stamp, loc, fixed_frame_, loc);
595  (*it).second.pos.header.stamp = header.stamp;
596  (*it).second.pos.pos.x = loc[0];
597  (*it).second.pos.pos.y = loc[1];
598  (*it).second.pos.pos.z = loc[2];
599  }
600  catch (tf::TransformException& ex)
601  {
602  }
603  it++;
604  }
605  }
606  // End filter face position update
607 
608  // Associate the found faces with previously seen faces, and publish all good face centers.
609  Box2D3D *one_face;
610  people_msgs::PositionMeasurement pos;
611  people_msgs::PositionMeasurementArray pos_array;
612 
613  for (uint iface = 0; iface < faces_vector.size(); iface++)
614  {
615  one_face = &faces_vector[iface];
616 
617  if (one_face->status == "good" || (one_face->status == "unknown" && do_publish_unknown_))
618  {
619  std::string id = "";
620 
621  // Convert the face format to a PositionMeasurement msg.
622  pos.header.stamp = header.stamp;
623  pos.name = name_;
624  pos.pos.x = one_face->center3d.x;
625  pos.pos.y = one_face->center3d.y;
626  pos.pos.z = one_face->center3d.z;
627  pos.header.frame_id = header.frame_id; // "*_optical_frame";
628  pos.reliability = reliability_;
629  pos.initialization = 1; // 0;
630  pos.covariance[0] = 0.04;
631  pos.covariance[1] = 0.0;
632  pos.covariance[2] = 0.0;
633  pos.covariance[3] = 0.0;
634  pos.covariance[4] = 0.04;
635  pos.covariance[5] = 0.0;
636  pos.covariance[6] = 0.0;
637  pos.covariance[7] = 0.0;
638  pos.covariance[8] = 0.04;
639 
640  // Check if this person's face is close enough to one of the previously known faces
641  // and associate it with the closest one.
642  // Otherwise publish it with an empty id.
643  // Note that multiple face positions can be published with the same id, but ids in the pos_list_ are unique.
644  // The position of a face in the list is updated with the closest found face.
645  double dist, mindist = BIGDIST_M;
646  std::map<std::string, RestampedPositionMeasurement>::iterator close_it = pos_list_.end();
647  for (it = pos_list_.begin(); it != pos_list_.end(); it++)
648  {
649  dist = pow((*it).second.pos.pos.x - pos.pos.x, 2.0) +
650  pow((*it).second.pos.pos.y - pos.pos.y, 2.0) +
651  pow((*it).second.pos.pos.z - pos.pos.z, 2.0);
652  if (dist <= faces_->face_sep_dist_m_ && dist < mindist)
653  {
654  mindist = dist;
655  close_it = it;
656  }
657  }
658  if (close_it != pos_list_.end())
659  {
660  pos.object_id = (*close_it).second.pos.object_id;
661  if (mindist < (*close_it).second.dist)
662  {
663  (*close_it).second.restamp = header.stamp;
664  (*close_it).second.dist = mindist;
665  (*close_it).second.pos = pos;
666  }
667  ROS_INFO_STREAM_NAMED("face_detector", "Found face to match with id " << pos.object_id);
668  }
669  else
670  {
671  max_id_++;
672  pos.object_id = static_cast<std::ostringstream*>(&(std::ostringstream() << max_id_))->str();
673  ROS_INFO_STREAM_NAMED("face_detector", "Didn't find face to match, starting new ID " << pos.object_id);
674  }
675  result_.face_positions.push_back(pos);
676  found_faces = true;
677  }
678  }
679  pos_array.header.stamp = header.stamp;
680  pos_array.header.frame_id = header.frame_id;
681  pos_array.people = result_.face_positions;
682  if (pos_array.people.size() > 0)
683  {
684  pos_array_pub_.publish(pos_array);
685 
686  // Update the position list greedily. This should be rewritten.
687  std::map<std::string, RestampedPositionMeasurement>::iterator it;
688  for (uint ipa = 0; ipa < pos_array.people.size(); ipa++)
689  {
690  it = pos_list_.find(pos_array.people[ipa].object_id);
692  rpm.pos = pos_array.people[ipa];
693  rpm.restamp = pos_array.people[ipa].header.stamp;
694  rpm.dist = BIGDIST_M;
695  if (it == pos_list_.end())
696  {
697  pos_list_.insert(std::pair<std::string, RestampedPositionMeasurement>(pos_array.people[ipa].object_id,
698  rpm));
699  }
700  else if ((pos_array.people[ipa].header.stamp - (*it).second.pos.header.stamp) > ros::Duration().fromSec(-1.0))
701  {
702  (*it).second = rpm;
703  }
704  }
705  // pos_lock.unlock();
706 
707  // Clean out all of the distances in the pos_list_
708  for (it = pos_list_.begin(); it != pos_list_.end(); it++)
709  {
710  (*it).second.dist = BIGDIST_M;
711  }
712  }
713 
714  // Done associating faces
715 
716  /******** Display **************************************************************/
717 
718  // Publish a point cloud of face centers.
719  cloud.channels.resize(1);
720  cloud.channels[0].name = "intensity";
721 
722  for (uint iface = 0; iface < faces_vector.size(); iface++)
723  {
724  one_face = &faces_vector[iface];
725 
726  // Visualization of good faces as a point cloud
727  if (one_face->status == "good")
728  {
729  geometry_msgs::Point32 p;
730  p.x = one_face->center3d.x;
731  p.y = one_face->center3d.y;
732  p.z = one_face->center3d.z;
733  cloud.points.push_back(p);
734  cloud.channels[0].values.push_back(1.0f);
735 
736  ngood++;
737  }
738  }
739 
740  cloud_pub_.publish(cloud);
741  // Done publishing the point cloud.
742  } // Done if faces_vector.size() > 0
743 
744  // Draw an appropriately colored rectangle on the display image and in the visualizer.
745  if (do_display_)
746  {
747  displayFacesOnImage(faces_vector);
748  cv_mutex_.unlock();
749  }
750  // Done drawing.
751 
752  /******** Done display **********************************************************/
753  ROS_INFO_STREAM_NAMED("face_detector", "Number of faces found: " << faces_vector.size() <<
754  ", number with good depth and size: " << ngood);
755 
756  // If you don't want continuous processing and you've found at least one face, turn off the detector.
757  if (!do_continuous_ && found_faces)
758  {
759  as_.setSucceeded(result_);
760  }
761  }
762 
763  // Draw bounding boxes around detected faces on the cv_image_out_ and show the image.
764  void displayFacesOnImage(std::vector<Box2D3D> faces_vector)
765  {
766  Box2D3D *one_face;
767 
768  for (uint iface = 0; iface < faces_vector.size(); iface++)
769  {
770  one_face = &faces_vector[iface];
771  // Visualization by image display.
772  if (do_display_)
773  {
774  cv::Scalar color;
775  if (one_face->status == "good")
776  {
777  color = cv::Scalar(0, 255, 0);
778  }
779  else if (one_face->status == "unknown")
780  {
781  color = cv::Scalar(255, 0, 0);
782  }
783  else
784  {
785  color = cv::Scalar(0, 0, 255);
786  }
787 
788  cv::rectangle(cv_image_out_,
789  cv::Point(one_face->box2d.x, one_face->box2d.y),
790  cv::Point(one_face->box2d.x + one_face->box2d.width,
791  one_face->box2d.y + one_face->box2d.height),
792  color, 4);
793  }
794  }
795 
796  cv::imshow("Face detector: Face Detection", cv_image_out_);
797  cv::waitKey(2);
798  }
799 }; // end class
800 }; // end namespace people
801 
802 // Main
803 int main(int argc, char **argv)
804 {
805  ros::init(argc, argv, "face_detector");
806 
808 
809  return 0;
810 }
void initFaceDetectionDepth(uint num_cascades, std::string haar_classifier_filename, double face_size_min_m, double face_size_max_m, double max_face_z_m, double face_sep_dist_m)
Initialize the face detector with images and depth.
Definition: faces.cpp:253
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
message_filters::Subscriber< sensor_msgs::CameraInfo > c2_info_sub_
image_transport::SubscriberFilter depth_image_sub_
#define FACE_SIZE_MIN_M
Definition: faces.h:57
boost::shared_ptr< const Goal > acceptNewGoal()
void matchAndDisplay(std::vector< Box2D3D > faces_vector, std_msgs::Header header)
image_geometry::StereoCameraModel cam_model_
A structure for holding information about boxes in 2d and 3d.
Definition: faces.h:69
std::vector< Box2D3D > detectAllFacesDepth(const cv::Mat &image, double threshold, const cv::Mat &depth_image, image_geometry::StereoCameraModel *cam_model)
Detect all faces in an image and depth image.
Definition: faces.cpp:275
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
boost::shared_ptr< ApproximateDepthSync > approximate_depth_sync_
static void pointMsgToTF(const geometry_msgs::Point &msg_v, Point &bt_v)
message_filters::Synchronizer< ExactDepthPolicy > ExactDepthSync
void publish(const boost::shared_ptr< M > &message) const
std::string status
Definition: faces.h:76
f
bool fromCameraInfo(const sensor_msgs::CameraInfo &left, const sensor_msgs::CameraInfo &right)
Time & fromNSec(uint64_t t)
boost::shared_ptr< ExactDispSync > exact_disp_sync_
face_detector::FaceDetectorFeedback feedback_
image_transport::ImageTransport it_
std::string resolveName(const std::string &name, bool remap=true) const
ros::Subscriber pos_sub_
XmlRpcServer s
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
#define FACE_SEP_DIST_M
Definition: faces.h:61
ROSCPP_DECL const std::string & getName()
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, stereo_msgs::DisparityImage, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > ApproximateDispPolicy
Definition: faces.h:63
cv::Point3d center3d
Definition: faces.h:72
void transformPoint(const std::string &target_frame, const geometry_msgs::PointStamped &stamped_in, geometry_msgs::PointStamped &stamped_out) const
#define ROS_INFO_STREAM_NAMED(name, args)
ROSCPP_DECL std::string clean(const std::string &name)
face_detector::FaceDetectorResult result_
message_filters::Synchronizer< ApproximateDispPolicy > ApproximateDispSync
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > ApproximateDepthPolicy
Position message callback.
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
std::string camera_info_topic_
ROSCPP_DECL void spin(Spinner &spinner)
#define FACE_SIZE_MAX_M
Definition: faces.h:58
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)
Image callback for synced messages.
FaceDetector(std::string name)
boost::mutex dimage_mutex_
cv::Rect box2d
Definition: faces.h:75
message_filters::Subscriber< sensor_msgs::CameraInfo > c1_info_sub_
ros::Publisher pos_array_pub_
message_filters::sync_policies::ExactTime< sensor_msgs::Image, stereo_msgs::DisparityImage, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > ExactDispPolicy
void setPreempted(const Result &result=Result(), const std::string &text=std::string(""))
message_filters::Synchronizer< ExactDispPolicy > ExactDispSync
tf::TransformListener tf_
Duration & fromSec(double t)
actionlib::SimpleActionServer< face_detector::FaceDetectorAction > as_
bool param(const std::string &param_name, T &param_val, const T &default_val) const
std::string disparity_topic_
std::string stereo_namespace_
void registerPreemptCallback(boost::function< void()> cb)
const Subscriber & getSubscriber() const
#define MAX_FACE_Z_M
Definition: faces.h:59
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
int main(int argc, char **argv)
void initFaceDetectionDisparity(uint num_cascades, std::string haar_classifier_filename, double face_size_min_m, double face_size_max_m, double max_face_z_m, double face_sep_dist_m)
Initialize the face detector with images and disparities.
Definition: faces.cpp:83
std::string left_camera_info_topic_
std::string right_camera_info_topic_
message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > ExactDepthPolicy
void subscribe(ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const TransportHints &transport_hints=TransportHints())
std::map< std::string, RestampedPositionMeasurement > pos_list_
uint32_t getNumSubscribers() const
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
boost::shared_ptr< ExactDepthSync > exact_depth_sync_
Contains a list of faces and functions that can be performed on that list. This includes utility task...
Definition: faces.h:93
boost::mutex limage_mutex_
std::string depth_info_topic_
ros::NodeHandle nh_
image_transport::SubscriberFilter image_sub_
boost::shared_ptr< ApproximateDispSync > approximate_disp_sync_
message_filters::Subscriber< stereo_msgs::DisparityImage > disp_image_sub_
void displayFacesOnImage(std::vector< Box2D3D > faces_vector)
void registerGoalCallback(boost::function< void()> cb)
boost::mutex connect_mutex_
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)
Image callback for synced messages.
ros::Publisher cloud_pub_
message_filters::Synchronizer< ApproximateDepthPolicy > ApproximateDepthSync
void operator()(void const *) const
std::vector< Box2D3D > detectAllFacesDisparity(const cv::Mat &image, double threshold, const cv::Mat &disparity_image, image_geometry::StereoCameraModel *cam_model)
Detect all faces in an image and disparity image.
Definition: faces.cpp:105
#define ROS_DEBUG(...)


face_detector
Author(s): Caroline Pantofaru
autogenerated on Sun Feb 21 2021 03:56:45