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 <ros/package.h>
49 #include <boost/filesystem.hpp>
50 #include <boost/thread/mutex.hpp>
51 
52 #include <people_msgs/PositionMeasurement.h>
53 #include <people_msgs/PositionMeasurementArray.h>
59 #include <sensor_msgs/CameraInfo.h>
60 #include <sensor_msgs/Image.h>
61 #include <stereo_msgs/DisparityImage.h>
63 #include <cv_bridge/cv_bridge.h>
64 #include <tf/transform_listener.h>
65 #include <sensor_msgs/PointCloud.h>
66 #include <geometry_msgs/Point32.h>
67 
68 #include <opencv2/core/core_c.h>
69 #include <opencv2/highgui.hpp>
70 #include <opencv2/highgui/highgui_c.h>
71 
72 #include <face_detector/faces.h>
73 
75 
77 #include <face_detector/FaceDetectorAction.h>
78 
79 #include <yaml-cpp/yaml.h>
80 
81 namespace people
82 {
83 bool fexists(const std::string& filename)
84 {
85  std::ifstream ifile(filename);
86  return ifile.is_open();
87 }
88 
89 std::string loadClassifierFilename(const ros::NodeHandle& local_nh)
90 {
91  std::string param_value;
92  local_nh.param("classifier_filename", param_value, std::string(""));
93  if (fexists(param_value))
94  {
95  return param_value;
96  }
97 
98  std::vector<std::string> folders;
99 
100  if (local_nh.hasParam("classifier_folders"))
101  {
102  local_nh.param("classifier_folders", folders);
103  }
104  else
105  {
106  YAML::Node folders_yaml = YAML::LoadFile(ros::package::getPath("face_detector") + "/param/default_folders.yaml");
107  for (YAML::const_iterator it = folders_yaml.begin(); it != folders_yaml.end(); ++it)
108  {
109  folders.push_back(it->as<std::string>());
110  }
111  }
112 
113  for (const std::string& folder : folders)
114  {
115  std::string path = folder + "/" + param_value;
116  if (fexists(path))
117  {
118  return path;
119  }
120  }
121 
122  ROS_FATAL("Cascade file %s doesn't exist.", param_value.c_str());
123  exit(-1);
124 }
125 
126 
129 class FaceDetector
130 {
131 public:
132  // Constants
133  const double BIGDIST_M; // = 1000000.0;
134 
135  // Node handle
137 
138  boost::mutex connect_mutex_;
139  bool use_rgbd_;
140 
141  // Subscription topics
142  std::string image_image_;
143  // Stereo
144  std::string stereo_namespace_;
145  std::string left_topic_;
146  std::string disparity_topic_;
147  std::string left_camera_info_topic_;
148  std::string right_camera_info_topic_;
149  // RGB-D
150  std::string camera_;
151  std::string camera_topic_;
152  std::string depth_image_;
153  std::string depth_topic_;
154  std::string camera_info_topic_;
155  std::string depth_info_topic_;
156  std::string rgb_ns_;
157  std::string depth_ns_;
158 
159  // Images and conversion for both the stereo camera and rgb-d camera cases.
167  // Disparity:
169  <sensor_msgs::Image, stereo_msgs::DisparityImage, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo>
172  <sensor_msgs::Image, stereo_msgs::DisparityImage, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo>
178 
179  // Depth:
181  <sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo>
184  <sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo>
190 
191  // Action
193  face_detector::FaceDetectorFeedback feedback_;
194  face_detector::FaceDetectorResult result_;
195 
196  // If running the face detector as a component in part of a larger person tracker,
197  // this subscribes to the tracker's position measurements and whether it was initialized by some other node.
198  // Todo: resurrect the person tracker.
200  bool external_init_;
201 
202  // Publishers
203  // A point cloud of the face positions, meant for visualization in rviz.
204  // This could be replaced by visualization markers, but they can't be modified
205  // in rviz at runtime (eg the alpha, display time, etc. can't be changed.)
208 
209  // Display
210  bool do_display_;
211  cv::Mat cv_image_out_;
213  // Depth
214  bool use_depth_;
217  // Face detector params and output
219  std::string name_;
220  std::string haar_filename_;
221  double reliability_;
224  {
226  people_msgs::PositionMeasurement pos;
227  double dist;
228  };
229  std::map<std::string, RestampedPositionMeasurement> pos_list_;
231  int max_id_;
232 
233  bool quit_;
234 
236 
237  std::string fixed_frame_;
238 
240 
241  bool do_continuous_;
244  // Will just use the image x, y in the pos field of the published position_measurement.
245 
246  explicit FaceDetector(std::string name) :
247  BIGDIST_M(1000000.0),
249  as_(nh_, name, false),
250  faces_(0),
251  max_id_(-1),
252  quit_(false)
253  {
254  ROS_INFO_STREAM_NAMED("face_detector", "Constructing FaceDetector.");
255 
256  // Action stuff
257  as_.registerGoalCallback(boost::bind(&FaceDetector::goalCB, this));
260 
261  faces_ = new Faces();
262  double face_size_min_m, face_size_max_m, max_face_z_m, face_sep_dist_m;
263  int queue_size;
264  bool approx;
265 
266  // Parameters
267  ros::NodeHandle local_nh("~");
268  local_nh.param("classifier_name", name_, std::string(""));
269  local_nh.param("classifier_reliability", reliability_, 0.0);
270  local_nh.param("do_display", do_display_, false);
271  local_nh.param("do_continuous", do_continuous_, true);
272  local_nh.param("do_publish_faces_of_unknown_size", do_publish_unknown_, false);
273  local_nh.param("use_depth", use_depth_, true);
274  local_nh.param("use_external_init", external_init_, false);
275  local_nh.param("face_size_min_m", face_size_min_m, FACE_SIZE_MIN_M);
276  local_nh.param("face_size_max_m", face_size_max_m, FACE_SIZE_MAX_M);
277  local_nh.param("max_face_z_m", max_face_z_m, MAX_FACE_Z_M);
278  local_nh.param("face_separation_dist_m", face_sep_dist_m, FACE_SEP_DIST_M);
279  local_nh.param("use_rgbd", use_rgbd_, false);
280  local_nh.param("queue_size", queue_size, 5);
281  local_nh.param("approximate_sync", approx, false);
282 
284 
285  if (do_display_)
286  {
287  // OpenCV: pop up an OpenCV highgui window
288  cv::namedWindow("Face detector: Face Detection", CV_WINDOW_AUTOSIZE);
289  }
290 
291  // Init the detector and subscribe to the images and camera parameters. One case for rgbd, one for stereo.
292  if (use_rgbd_)
293  {
295  face_size_min_m, face_size_max_m, max_face_z_m, face_sep_dist_m);
296 
297  camera_ = nh_.resolveName("camera");
298  image_image_ = nh_.resolveName("image_topic");
299  depth_image_ = nh_.resolveName("depth_topic");
300  rgb_ns_ = nh_.resolveName("rgb_ns");
301  depth_ns_ = nh_.resolveName("depth_ns");
304  camera_info_topic_ = ros::names::clean(camera_ + "/" + rgb_ns_ + "/camera_info");
305  depth_info_topic_ = ros::names::clean(camera_ + "/" + depth_ns_ + "/camera_info");
306 
307  ROS_DEBUG("camera_topic_: %s", camera_topic_.c_str());
308  ROS_DEBUG("depth_topic_: %s", depth_topic_.c_str());
309  ROS_DEBUG("camera_info_topic_: %s", camera_info_topic_.c_str());
310  ROS_DEBUG("depth_info_topic_: %s", depth_info_topic_.c_str());
311 
312  local_nh.param("fixed_frame", fixed_frame_, std::string("camera_rgb_optical_frame"));
313 
314  if (approx)
315  {
318  approximate_depth_sync_->registerCallback(boost::bind(&FaceDetector::imageCBAllDepth,
319  this, _1, _2, _3, _4));
320  }
321  else
322  {
323  exact_depth_sync_.reset(new ExactDepthSync(ExactDepthPolicy(queue_size),
325  exact_depth_sync_->registerCallback(boost::bind(&FaceDetector::imageCBAllDepth,
326  this, _1, _2, _3, _4));
327  }
328  }
329  else
330  {
332  face_size_min_m, face_size_max_m, max_face_z_m, face_sep_dist_m);
333 
334  stereo_namespace_ = nh_.resolveName("camera");
335  image_image_ = nh_.resolveName("image_topic");
340 
341  local_nh.param("fixed_frame", fixed_frame_, stereo_namespace_.append("_optical_frame"));
342 
343  if (approx)
344  {
347  approximate_disp_sync_->registerCallback(boost::bind(&FaceDetector::imageCBAllDisp,
348  this, _1, _2, _3, _4));
349  }
350  else
351  {
352  exact_disp_sync_.reset(new ExactDispSync(ExactDispPolicy(queue_size),
354  exact_disp_sync_->registerCallback(boost::bind(&FaceDetector::imageCBAllDisp,
355  this, _1, _2, _3, _4));
356  }
357  }
358 
359  // Connection callbacks and advertise
360  ros::SubscriberStatusCallback pos_pub_connect_cb = boost::bind(&FaceDetector::connectCb, this);
361  ros::SubscriberStatusCallback cloud_pub_connect_cb = boost::bind(&FaceDetector::connectCb, this);
362  if (do_continuous_)
363  ROS_INFO_STREAM_NAMED("face_detector", "You must subscribe to one of FaceDetector's outbound topics "
364  "or else it will not publish anything.");
365 
366  {
367  boost::mutex::scoped_lock lock(connect_mutex_);
368 
369  // Advertise a position measure message.
370  pos_array_pub_ = nh_.advertise<people_msgs::PositionMeasurementArray>(
371  "face_detector/people_tracker_measurements_array", 1, pos_pub_connect_cb, pos_pub_connect_cb);
372 
373  cloud_pub_ = nh_.advertise<sensor_msgs::PointCloud>("face_detector/faces_cloud", 0,
374  cloud_pub_connect_cb, cloud_pub_connect_cb);
375  }
376 
377  // If running as an action server, just stay connected so that action calls are fast.
378  if (!do_continuous_) connectCb();
379 
381  ros::spin(s);
382  }
383 
384  ~FaceDetector()
385  {
386  cv_image_out_.release();
387 
388  if (do_display_)
389  {
390  cv::destroyWindow("Face detector: Face Detection");
391  }
392 
393  if (faces_)
394  {
395  delete faces_;
396  faces_ = 0;
397  }
398  }
399 
400  // Handles (un)subscribing when clients (un)subscribe
401  void connectCb()
402  {
403  boost::mutex::scoped_lock lock(connect_mutex_);
404  if (use_rgbd_)
405  {
407  {
408  ROS_INFO_STREAM_NAMED("face_detector", "You have unsubscribed to FaceDetector's outbound topics, "
409  "so it will no longer publish anything.");
414  pos_sub_.shutdown();
415  }
416  else if (!do_continuous_ || !image_sub_.getSubscriber())
417  {
422  // // Subscribe to filter measurements.
423  // if (external_init_) {
424  // //pos_sub_ = nh_.subscribe("people_tracker_filter",1,&FaceDetector::posCallback,this);
425  // pos_sub_ = nh_.subscribe("/face_detector/people_tracker_measurements_array",
426  // 1,&FaceDetector::posCallback,this);
427  // }
428  }
429  }
430  else
431  {
433  {
434  ROS_INFO_STREAM_NAMED("face_detector", "You have unsubscribed to FaceDetector's outbound topics, "
435  "so it will no longer publish anything.");
440  pos_sub_.shutdown();
441  }
442  else if (!do_continuous_ || !image_sub_.getSubscriber())
443  {
448  // // Subscribe to filter measurements.
449  // if (external_init_) {
450  // //pos_sub_ = nh_.subscribe("people_tracker_filter",1,&FaceDetector::posCallback,this);
451  // pos_sub_ = nh_.subscribe("/face_detector/people_tracker_measurements_array",1,
452  // &FaceDetector::posCallback,this);
453  // }
454  }
455  }
456  }
457 
458  void goalCB()
459  {
460  as_.acceptNewGoal();
461  }
462 
463  void preemptCB()
464  {
465  as_.setPreempted();
466  }
467 
474  // void posCallback(const people_msgs::PositionMeasurementArrayConstPtr& pos_array_ptr) {
475 
476  // // Put the incoming position into the position queue. It'll be processed in the next image callback.
477  // boost::mutex::scoped_lock lock(pos_mutex_);
478 
479  // std::map<std::string, RestampedPositionMeasurement>::iterator it;
480  // for (uint ipa = 0; ipa < pos_array_ptr->people.size(); ipa++) {
481  // it = pos_list_.find(pos_array_ptr->people[ipa].object_id);
482  // RestampedPositionMeasurement rpm;
483  // rpm.pos = pos_array_ptr->people[ipa];
484  // rpm.restamp = pos_array_ptr->people[ipa].header.stamp;
485  // rpm.dist = BIGDIST_M;
486  // if (it == pos_list_.end()) {
487  // pos_list_.insert(pair<std::string, RestampedPositionMeasurement>(pos_array_ptr->people[ipa].object_id, rpm));
488  // }
489  // else if ((pos_array_ptr->people[ipa].header.stamp - (*it).second.pos.header.stamp) >
490  // ros::Duration().fromSec(-1.0) ){
491  // (*it).second = rpm;
492  // }
493  // }
494  // lock.unlock();
495 
496  // }
497 
498  // Workaround to convert a DisparityImage->Image into a shared pointer for cv_bridge in imageCBAll.
499  struct NullDeleter
500  {
501  void operator()(void const *) const {}
502  };
503 
513  void imageCBAllDepth(const sensor_msgs::Image::ConstPtr &image,
514  const sensor_msgs::Image::ConstPtr& depth_image,
515  const sensor_msgs::CameraInfo::ConstPtr& c1_info,
516  const sensor_msgs::CameraInfo::ConstPtr& c2_info)
517  {
518  // Only run the detector if in continuous mode or the detector was turned on through an action invocation.
519  if (!do_continuous_ && !as_.isActive())
520  return;
521 
522  // Clear out the result vector.
523  result_.face_positions.clear();
524 
525  if (do_display_)
526  {
527  cv_mutex_.lock();
528  }
529 
530  // ROS --> OpenCV
531  cv_bridge::CvImageConstPtr cv_image_ptr = cv_bridge::toCvShare(image, "bgr8");
533  cv::Mat depth_32fc1 = cv_depth_ptr->image;
534  if (depth_image->encoding != "32FC1")
535  {
536  cv_depth_ptr->image.convertTo(depth_32fc1, CV_32FC1, 0.001);
537  }
538 
539  cam_model_.fromCameraInfo(c1_info, c2_info);
540 
541  // For display, keep a copy of the image that we can draw on.
542  if (do_display_)
543  {
544  cv_image_out_ = (cv_image_ptr->image).clone();
545  }
546 
547  struct timeval timeofday;
548  gettimeofday(&timeofday, NULL);
549  ros::Time starttdetect = ros::Time().fromNSec(1e9 * timeofday.tv_sec + 1e3 * timeofday.tv_usec);
550 
551  std::vector<Box2D3D> faces_vector = faces_->detectAllFacesDepth(cv_image_ptr->image, 1.0, depth_32fc1, &cam_model_);
552  gettimeofday(&timeofday, NULL);
553  ros::Time endtdetect = ros::Time().fromNSec(1e9 * timeofday.tv_sec + 1e3 * timeofday.tv_usec);
554  ros::Duration diffdetect = endtdetect - starttdetect;
555  ROS_INFO_STREAM_NAMED("face_detector", "Detection duration = " << diffdetect.toSec() << "sec");
556 
557  matchAndDisplay(faces_vector, image->header);
558  }
559 
568  void imageCBAllDisp(const sensor_msgs::Image::ConstPtr &image,
569  const stereo_msgs::DisparityImage::ConstPtr& disp_image,
570  const sensor_msgs::CameraInfo::ConstPtr& c1_info,
571  const sensor_msgs::CameraInfo::ConstPtr& c2_info)
572  {
573  // Only run the detector if in continuous mode or the detector was turned on through an action invocation.
574  if (!do_continuous_ && !as_.isActive())
575  return;
576 
577  // Clear out the result vector.
578  result_.face_positions.clear();
579 
580  if (do_display_)
581  {
582  cv_mutex_.lock();
583  }
584 
585  // ROS --> OpenCV
587  cv_bridge::CvImageConstPtr cv_disp_ptr = cv_bridge::toCvShare(disp_image->image, disp_image);
588  cam_model_.fromCameraInfo(c1_info, c2_info);
589 
590  // For display, keep a copy of the image that we can draw on.
591  if (do_display_)
592  {
593  cv_image_out_ = (cv_image_ptr->image).clone();
594  }
595 
596  struct timeval timeofday;
597  gettimeofday(&timeofday, NULL);
598  ros::Time starttdetect = ros::Time().fromNSec(1e9 * timeofday.tv_sec + 1e3 * timeofday.tv_usec);
599 
600  std::vector<Box2D3D> faces_vector = faces_->detectAllFacesDisparity(cv_image_ptr->image, 1.0,
601  cv_disp_ptr->image, &cam_model_);
602  gettimeofday(&timeofday, NULL);
603  ros::Time endtdetect = ros::Time().fromNSec(1e9 * timeofday.tv_sec + 1e3 * timeofday.tv_usec);
604  ros::Duration diffdetect = endtdetect - starttdetect;
605  ROS_INFO_STREAM_NAMED("face_detector", "Detection duration = " << diffdetect.toSec() << "sec");
606 
607  matchAndDisplay(faces_vector, image->header);
608  }
609 
610 private:
611  void matchAndDisplay(std::vector<Box2D3D> faces_vector, std_msgs::Header header)
612  {
613  bool found_faces = false;
614 
615  int ngood = 0;
616  sensor_msgs::PointCloud cloud;
617  cloud.header.stamp = header.stamp;
618  cloud.header.frame_id = header.frame_id;
619 
620  if (faces_vector.size() > 0)
621  {
622  // Transform the positions of the known faces and remove anyone who hasn't had an update in a long time.
623  // boost::mutex::scoped_lock pos_lock(pos_mutex_);
624  std::map<std::string, RestampedPositionMeasurement>::iterator it;
625  it = pos_list_.begin();
626  while (it != pos_list_.end())
627  {
628  if ((header.stamp - (*it).second.restamp) > ros::Duration().fromSec(5.0))
629  {
630  // Position is too old, remove the person.
631  pos_list_.erase(it++);
632  }
633  else
634  {
635  // Transform the person to this time. Note that the pos time is updated but not the restamp.
636  tf::Point pt;
637  tf::pointMsgToTF((*it).second.pos.pos, pt);
638  tf::Stamped<tf::Point> loc(pt, (*it).second.pos.header.stamp, (*it).second.pos.header.frame_id);
639  try
640  {
641  tf_.transformPoint(header.frame_id, header.stamp, loc, fixed_frame_, loc);
642  (*it).second.pos.header.stamp = header.stamp;
643  (*it).second.pos.pos.x = loc[0];
644  (*it).second.pos.pos.y = loc[1];
645  (*it).second.pos.pos.z = loc[2];
646  }
647  catch (tf::TransformException& ex)
648  {
649  }
650  it++;
651  }
652  }
653  // End filter face position update
654 
655  // Associate the found faces with previously seen faces, and publish all good face centers.
656  Box2D3D *one_face;
657  people_msgs::PositionMeasurement pos;
658  people_msgs::PositionMeasurementArray pos_array;
659 
660  for (uint iface = 0; iface < faces_vector.size(); iface++)
661  {
662  one_face = &faces_vector[iface];
663 
664  if (one_face->status == "good" || (one_face->status == "unknown" && do_publish_unknown_))
665  {
666  std::string id = "";
667 
668  // Convert the face format to a PositionMeasurement msg.
669  pos.header.stamp = header.stamp;
670  pos.name = name_;
671  pos.pos.x = one_face->center3d.x;
672  pos.pos.y = one_face->center3d.y;
673  pos.pos.z = one_face->center3d.z;
674  pos.header.frame_id = header.frame_id; // "*_optical_frame";
675  pos.reliability = reliability_;
676  pos.initialization = 1; // 0;
677  pos.covariance[0] = 0.04;
678  pos.covariance[1] = 0.0;
679  pos.covariance[2] = 0.0;
680  pos.covariance[3] = 0.0;
681  pos.covariance[4] = 0.04;
682  pos.covariance[5] = 0.0;
683  pos.covariance[6] = 0.0;
684  pos.covariance[7] = 0.0;
685  pos.covariance[8] = 0.04;
686 
687  // Check if this person's face is close enough to one of the previously known faces
688  // and associate it with the closest one.
689  // Otherwise publish it with an empty id.
690  // Note that multiple face positions can be published with the same id, but ids in the pos_list_ are unique.
691  // The position of a face in the list is updated with the closest found face.
692  double dist, mindist = BIGDIST_M;
693  std::map<std::string, RestampedPositionMeasurement>::iterator close_it = pos_list_.end();
694  for (it = pos_list_.begin(); it != pos_list_.end(); it++)
695  {
696  dist = pow((*it).second.pos.pos.x - pos.pos.x, 2.0) +
697  pow((*it).second.pos.pos.y - pos.pos.y, 2.0) +
698  pow((*it).second.pos.pos.z - pos.pos.z, 2.0);
699  if (dist <= faces_->face_sep_dist_m_ && dist < mindist)
700  {
701  mindist = dist;
702  close_it = it;
703  }
704  }
705  if (close_it != pos_list_.end())
706  {
707  pos.object_id = (*close_it).second.pos.object_id;
708  if (mindist < (*close_it).second.dist)
709  {
710  (*close_it).second.restamp = header.stamp;
711  (*close_it).second.dist = mindist;
712  (*close_it).second.pos = pos;
713  }
714  ROS_INFO_STREAM_NAMED("face_detector", "Found face to match with id " << pos.object_id);
715  }
716  else
717  {
718  max_id_++;
719  pos.object_id = static_cast<std::ostringstream*>(&(std::ostringstream() << max_id_))->str();
720  ROS_INFO_STREAM_NAMED("face_detector", "Didn't find face to match, starting new ID " << pos.object_id);
721  }
722  result_.face_positions.push_back(pos);
723  found_faces = true;
724  }
725  }
726  pos_array.header.stamp = header.stamp;
727  pos_array.header.frame_id = header.frame_id;
728  pos_array.people = result_.face_positions;
729  if (pos_array.people.size() > 0)
730  {
731  pos_array_pub_.publish(pos_array);
732 
733  // Update the position list greedily. This should be rewritten.
734  std::map<std::string, RestampedPositionMeasurement>::iterator it;
735  for (uint ipa = 0; ipa < pos_array.people.size(); ipa++)
736  {
737  it = pos_list_.find(pos_array.people[ipa].object_id);
738  RestampedPositionMeasurement rpm;
739  rpm.pos = pos_array.people[ipa];
740  rpm.restamp = pos_array.people[ipa].header.stamp;
741  rpm.dist = BIGDIST_M;
742  if (it == pos_list_.end())
743  {
744  pos_list_.insert(std::pair<std::string, RestampedPositionMeasurement>(pos_array.people[ipa].object_id,
745  rpm));
746  }
747  else if ((pos_array.people[ipa].header.stamp - (*it).second.pos.header.stamp) > ros::Duration().fromSec(-1.0))
748  {
749  (*it).second = rpm;
750  }
751  }
752  // pos_lock.unlock();
753 
754  // Clean out all of the distances in the pos_list_
755  for (it = pos_list_.begin(); it != pos_list_.end(); it++)
756  {
757  (*it).second.dist = BIGDIST_M;
758  }
759  }
760 
761  // Done associating faces
762 
763  /******** Display **************************************************************/
764 
765  // Publish a point cloud of face centers.
766  cloud.channels.resize(1);
767  cloud.channels[0].name = "intensity";
768 
769  for (uint iface = 0; iface < faces_vector.size(); iface++)
770  {
771  one_face = &faces_vector[iface];
772 
773  // Visualization of good faces as a point cloud
774  if (one_face->status == "good")
775  {
776  geometry_msgs::Point32 p;
777  p.x = one_face->center3d.x;
778  p.y = one_face->center3d.y;
779  p.z = one_face->center3d.z;
780  cloud.points.push_back(p);
781  cloud.channels[0].values.push_back(1.0f);
782 
783  ngood++;
784  }
785  }
786 
787  cloud_pub_.publish(cloud);
788  // Done publishing the point cloud.
789  } // Done if faces_vector.size() > 0
790 
791  // Draw an appropriately colored rectangle on the display image and in the visualizer.
792  if (do_display_)
793  {
794  displayFacesOnImage(faces_vector);
795  cv_mutex_.unlock();
796  }
797  // Done drawing.
798 
799  /******** Done display **********************************************************/
800  ROS_INFO_STREAM_NAMED("face_detector", "Number of faces found: " << faces_vector.size() <<
801  ", number with good depth and size: " << ngood);
802 
803  // If you don't want continuous processing and you've found at least one face, turn off the detector.
804  if (!do_continuous_ && found_faces)
805  {
807  }
808  }
809 
810  // Draw bounding boxes around detected faces on the cv_image_out_ and show the image.
811  void displayFacesOnImage(std::vector<Box2D3D> faces_vector)
812  {
813  Box2D3D *one_face;
814 
815  for (uint iface = 0; iface < faces_vector.size(); iface++)
816  {
817  one_face = &faces_vector[iface];
818  // Visualization by image display.
819  if (do_display_)
820  {
821  cv::Scalar color;
822  if (one_face->status == "good")
823  {
824  color = cv::Scalar(0, 255, 0);
825  }
826  else if (one_face->status == "unknown")
827  {
828  color = cv::Scalar(255, 0, 0);
829  }
830  else
831  {
832  color = cv::Scalar(0, 0, 255);
833  }
834 
835  cv::rectangle(cv_image_out_,
836  cv::Point(one_face->box2d.x, one_face->box2d.y),
837  cv::Point(one_face->box2d.x + one_face->box2d.width,
838  one_face->box2d.y + one_face->box2d.height),
839  color, 4);
840  }
841  }
842 
843  cv::imshow("Face detector: Face Detection", cv_image_out_);
844  cv::waitKey(2);
845  }
846 }; // end class
847 }; // end namespace people
848 
849 // Main
850 int main(int argc, char **argv)
851 {
852  ros::init(argc, argv, "face_detector");
853 
855 
856  return 0;
857 }
people::FaceDetector::ExactDepthPolicy
message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > ExactDepthPolicy
Definition: face_detection.cpp:215
people::FaceDetector
Definition: face_detection.cpp:162
image_transport::SubscriberFilter
ros::MultiThreadedSpinner
people::FaceDetector::limage_mutex_
boost::mutex limage_mutex_
Definition: face_detection.cpp:272
people::Faces::detectAllFacesDisparity
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:142
people::FaceDetector::ApproximateDispSync
message_filters::Synchronizer< ApproximateDispPolicy > ApproximateDispSync
Definition: face_detection.cpp:208
FACE_SIZE_MIN_M
#define FACE_SIZE_MIN_M
Definition: faces.h:56
ros::Publisher
DurationBase< Duration >::fromSec
Duration & fromSec(double t)
ros::package::getPath
ROSLIB_DECL std::string getPath(const std::string &package_name)
image_encodings.h
people::FaceDetector::cv_mutex_
boost::mutex cv_mutex_
Definition: face_detection.cpp:272
image_transport::ImageTransport
people::FaceDetector::stereo_namespace_
std::string stereo_namespace_
Definition: face_detection.cpp:177
people::FaceDetector::preemptCB
void preemptCB()
Definition: face_detection.cpp:496
people::FaceDetector::left_topic_
std::string left_topic_
Definition: face_detection.cpp:178
message_filters::Synchronizer
people::FaceDetector::~FaceDetector
~FaceDetector()
Definition: face_detection.cpp:417
boost::shared_ptr
people::FaceDetector::quit_
bool quit_
Definition: face_detection.cpp:266
people::FaceDetector::do_continuous_
bool do_continuous_
Definition: face_detection.cpp:274
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
people::FaceDetector::max_id_
int max_id_
Definition: face_detection.cpp:264
actionlib::SimpleActionServer::start
void start()
people::Faces::detectAllFacesDepth
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:312
people::FaceDetector::result_
face_detector::FaceDetectorResult result_
Definition: face_detection.cpp:227
people::FaceDetector::cv_image_out_
cv::Mat cv_image_out_
Definition: face_detection.cpp:244
s
XmlRpcServer s
ros.h
people::FaceDetector::external_init_
bool external_init_
Definition: face_detection.cpp:233
people::FaceDetector::RestampedPositionMeasurement::dist
double dist
Definition: face_detection.cpp:260
people::FaceDetector::ExactDispPolicy
message_filters::sync_policies::ExactTime< sensor_msgs::Image, stereo_msgs::DisparityImage, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > ExactDispPolicy
Definition: face_detection.cpp:203
people::FaceDetector::camera_info_topic_
std::string camera_info_topic_
Definition: face_detection.cpp:187
people::FaceDetector::matchAndDisplay
void matchAndDisplay(std::vector< Box2D3D > faces_vector, std_msgs::Header header)
Definition: face_detection.cpp:644
people::FaceDetector::exact_depth_sync_
boost::shared_ptr< ExactDepthSync > exact_depth_sync_
Definition: face_detection.cpp:221
ros::names::clean
ROSCPP_DECL std::string clean(const std::string &name)
tf::TransformListener::transformPoint
void transformPoint(const std::string &target_frame, const geometry_msgs::PointStamped &stamped_in, geometry_msgs::PointStamped &stamped_out) const
people::FaceDetector::tf_
tf::TransformListener tf_
Definition: face_detection.cpp:268
people::FaceDetector::cam_model_
image_geometry::StereoCameraModel cam_model_
Definition: face_detection.cpp:248
image_transport::SubscriberFilter::subscribe
void subscribe(ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const TransportHints &transport_hints=TransportHints())
simple_action_server.h
ros::Subscriber::shutdown
void shutdown()
time_synchronizer.h
people::FaceDetector::c1_info_sub_
message_filters::Subscriber< sensor_msgs::CameraInfo > c1_info_sub_
Definition: face_detection.cpp:197
people::FaceDetector::left_camera_info_topic_
std::string left_camera_info_topic_
Definition: face_detection.cpp:180
ros::SubscriberStatusCallback
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
people::FaceDetector::pos_mutex_
boost::mutex pos_mutex_
Definition: face_detection.cpp:272
people::FaceDetector::imageCBAllDisp
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.
Definition: face_detection.cpp:601
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
message_filters::Subscriber::unsubscribe
void unsubscribe()
actionlib::SimpleActionServer::setSucceeded
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
people::FaceDetector::it_
image_transport::ImageTransport it_
Definition: face_detection.cpp:193
MAX_FACE_Z_M
#define MAX_FACE_Z_M
Definition: faces.h:58
stereo_camera_model.h
people::FaceDetector::as_
actionlib::SimpleActionServer< face_detector::FaceDetectorAction > as_
Definition: face_detection.cpp:225
people::FaceDetector::image_image_
std::string image_image_
Definition: face_detection.cpp:175
message_filters::Subscriber< stereo_msgs::DisparityImage >
people::FaceDetector::NullDeleter
Position message callback.
Definition: face_detection.cpp:532
people::FaceDetector::haar_filename_
std::string haar_filename_
Definition: face_detection.cpp:253
people::FaceDetector::nh_
ros::NodeHandle nh_
Definition: face_detection.cpp:169
people::FaceDetector::pos_list_
std::map< std::string, RestampedPositionMeasurement > pos_list_
Definition: face_detection.cpp:262
people::FaceDetector::depth_image_sub_
image_transport::SubscriberFilter depth_image_sub_
Definition: face_detection.cpp:195
tf::Stamped
people::FaceDetector::use_rgbd_
bool use_rgbd_
Definition: face_detection.cpp:172
people::FaceDetector::right_camera_info_topic_
std::string right_camera_info_topic_
Definition: face_detection.cpp:181
ros::NodeHandle::resolveName
std::string resolveName(const std::string &name, bool remap=true) const
console.h
message_filters::sync_policies::ApproximateTime
tf::Point
tf::Vector3 Point
people::FaceDetector::displayFacesOnImage
void displayFacesOnImage(std::vector< Box2D3D > faces_vector)
Definition: face_detection.cpp:844
subscriber_filter.h
people::FaceDetector::approximate_depth_sync_
boost::shared_ptr< ApproximateDepthSync > approximate_depth_sync_
Definition: face_detection.cpp:222
people::FaceDetector::c2_info_sub_
message_filters::Subscriber< sensor_msgs::CameraInfo > c2_info_sub_
Definition: face_detection.cpp:198
people::FaceDetector::approximate_disp_sync_
boost::shared_ptr< ApproximateDispSync > approximate_disp_sync_
Definition: face_detection.cpp:210
people::FaceDetector::image_sub_
image_transport::SubscriberFilter image_sub_
Definition: face_detection.cpp:194
ROS_DEBUG
#define ROS_DEBUG(...)
people::FaceDetector::do_publish_unknown_
bool do_publish_unknown_
Definition: face_detection.cpp:276
people::FaceDetector::faces_
Faces * faces_
Definition: face_detection.cpp:251
subscriber.h
people::FaceDetector::cloud_pub_
ros::Publisher cloud_pub_
Definition: face_detection.cpp:239
actionlib::SimpleActionServer::isActive
bool isActive()
FACE_SEP_DIST_M
#define FACE_SEP_DIST_M
Definition: faces.h:60
people
Definition: faces.h:62
image_geometry::StereoCameraModel
people::FaceDetector::depth_image_
std::string depth_image_
Definition: face_detection.cpp:185
FACE_SIZE_MAX_M
#define FACE_SIZE_MAX_M
Definition: faces.h:57
ros::NodeHandle::hasParam
bool hasParam(const std::string &key) const
people::FaceDetector::RestampedPositionMeasurement::restamp
ros::Time restamp
Definition: face_detection.cpp:258
people::FaceDetector::do_display_
bool do_display_
Definition: face_detection.cpp:243
people::FaceDetector::FaceDetector
FaceDetector(std::string name)
Definition: face_detection.cpp:279
people::FaceDetector::reliability_
double reliability_
Definition: face_detection.cpp:254
actionlib::SimpleActionServer::registerPreemptCallback
void registerPreemptCallback(boost::function< void()> cb)
people::FaceDetector::depth_topic_
std::string depth_topic_
Definition: face_detection.cpp:186
people::FaceDetector::connectCb
void connectCb()
Definition: face_detection.cpp:434
actionlib::SimpleActionServer::setPreempted
void setPreempted(const Result &result=Result(), const std::string &text=std::string(""))
package.h
ROS_FATAL
#define ROS_FATAL(...)
people::FaceDetector::connect_mutex_
boost::mutex connect_mutex_
Definition: face_detection.cpp:171
people::FaceDetector::ExactDepthSync
message_filters::Synchronizer< ExactDepthPolicy > ExactDepthSync
Definition: face_detection.cpp:219
people::FaceDetector::name_
std::string name_
Definition: face_detection.cpp:252
exact_time.h
people::FaceDetector::dimage_mutex_
boost::mutex dimage_mutex_
Definition: face_detection.cpp:272
message_filters::Subscriber::subscribe
void subscribe()
actionlib::SimpleActionServer::registerGoalCallback
void registerGoalCallback(boost::function< void()> cb)
ros::this_node::getName
const ROSCPP_DECL std::string & getName()
transform_listener.h
people::FaceDetector::BIGDIST_M
const double BIGDIST_M
Definition: face_detection.cpp:166
people::FaceDetector::depth_ns_
std::string depth_ns_
Definition: face_detection.cpp:190
people::FaceDetector::RestampedPositionMeasurement
Definition: face_detection.cpp:256
people::loadClassifierFilename
std::string loadClassifierFilename(const ros::NodeHandle &local_nh)
Definition: face_detection.cpp:122
people::FaceDetector::ApproximateDepthPolicy
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > ApproximateDepthPolicy
Definition: face_detection.cpp:218
people::FaceDetector::disp_image_sub_
message_filters::Subscriber< stereo_msgs::DisparityImage > disp_image_sub_
Definition: face_detection.cpp:196
people::FaceDetector::fixed_frame_
std::string fixed_frame_
Definition: face_detection.cpp:270
faces.h
people::FaceDetector::ApproximateDepthSync
message_filters::Synchronizer< ApproximateDepthPolicy > ApproximateDepthSync
Definition: face_detection.cpp:220
people::FaceDetector::goalCB
void goalCB()
Definition: face_detection.cpp:491
people::FaceDetector::feedback_
face_detector::FaceDetectorFeedback feedback_
Definition: face_detection.cpp:226
TimeBase< Time, Duration >::fromNSec
Time & fromNSec(uint64_t t)
ros::Time
people::Faces
Contains a list of faces and functions that can be performed on that list. This includes utility task...
Definition: faces.h:92
people::Faces::initFaceDetectionDisparity
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:120
people::FaceDetector::use_depth_
bool use_depth_
Definition: face_detection.cpp:247
people::FaceDetector::NullDeleter::operator()
void operator()(void const *) const
Definition: face_detection.cpp:534
actionlib::SimpleActionServer::acceptNewGoal
boost::shared_ptr< const Goal > acceptNewGoal()
tf::pointMsgToTF
static void pointMsgToTF(const geometry_msgs::Point &msg_v, Point &bt_v)
actionlib::SimpleActionServer< face_detector::FaceDetectorAction >
cv_bridge.h
image_transport::SubscriberFilter::getSubscriber
const Subscriber & getSubscriber() const
people::FaceDetector::disparity_topic_
std::string disparity_topic_
Definition: face_detection.cpp:179
people::FaceDetector::pos_array_pub_
ros::Publisher pos_array_pub_
Definition: face_detection.cpp:240
people::FaceDetector::rgb_ns_
std::string rgb_ns_
Definition: face_detection.cpp:189
tf::TransformListener
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
people::FaceDetector::camera_topic_
std::string camera_topic_
Definition: face_detection.cpp:184
ROS_INFO_STREAM_NAMED
#define ROS_INFO_STREAM_NAMED(name, args)
people::FaceDetector::ApproximateDispPolicy
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, stereo_msgs::DisparityImage, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > ApproximateDispPolicy
Definition: face_detection.cpp:206
image_geometry::StereoCameraModel::fromCameraInfo
bool fromCameraInfo(const sensor_msgs::CameraInfo &left, const sensor_msgs::CameraInfo &right)
approximate_time.h
ros::spin
ROSCPP_DECL void spin()
sensor_msgs::image_encodings::BGR8
const std::string BGR8
people::FaceDetector::camera_
std::string camera_
Definition: face_detection.cpp:183
people::fexists
bool fexists(const std::string &filename)
Definition: face_detection.cpp:116
people::FaceDetector::ExactDispSync
message_filters::Synchronizer< ExactDispPolicy > ExactDispSync
Definition: face_detection.cpp:207
ros::Publisher::getNumSubscribers
uint32_t getNumSubscribers() const
DurationBase< Duration >::toSec
double toSec() const
people::FaceDetector::imageCBAllDepth
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.
Definition: face_detection.cpp:546
cv_bridge::toCvShare
CvImageConstPtr toCvShare(const sensor_msgs::Image &source, const boost::shared_ptr< void const > &tracked_object, const std::string &encoding=std::string())
message_filters::sync_policies::ExactTime
header
const std::string header
people::Faces::initFaceDetectionDepth
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:290
tf2::TransformException
main
int main(int argc, char **argv)
Definition: face_detection.cpp:850
ros::Duration
people::FaceDetector::pos_sub_
ros::Subscriber pos_sub_
Definition: face_detection.cpp:232
people::FaceDetector::RestampedPositionMeasurement::pos
people_msgs::PositionMeasurement pos
Definition: face_detection.cpp:259
people::FaceDetector::depth_info_topic_
std::string depth_info_topic_
Definition: face_detection.cpp:188
image_transport::SubscriberFilter::unsubscribe
void unsubscribe()
ros::NodeHandle
ros::Subscriber
people::FaceDetector::exact_disp_sync_
boost::shared_ptr< ExactDispSync > exact_disp_sync_
Definition: face_detection.cpp:209


face_detector
Author(s): Caroline Pantofaru
autogenerated on Wed Mar 2 2022 00:45:07