face_recognition_nodelet.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2017, Yuki Furuta.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Kei Okada nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 #include <algorithm>
36 #include <boost/filesystem.hpp>
37 #include <boost/shared_ptr.hpp>
38 #include <boost/thread.hpp>
39 #include <boost/version.hpp>
40 #include <iomanip>
41 #include <map>
42 #include <stdexcept>
43 #include <string>
44 #include <opencv2/opencv.hpp>
45 #include <pwd.h>
46 #include <vector>
47 
48 #include <cv_bridge/cv_bridge.h>
49 #include <dynamic_reconfigure/server.h>
57 
58 #include <opencv_apps/nodelet.h>
59 #include <opencv_apps/FaceArrayStamped.h>
60 #include <opencv_apps/FaceRecognitionTrain.h>
61 #include <opencv_apps/FaceRecognitionConfig.h>
62 
64 #if BOOST_VERSION < 105000
65 namespace fs = boost::filesystem3; // for hydro
66 #else
67 namespace fs = boost::filesystem;
68 #endif
69 
70 #if CV_MAJOR_VERSION >= 3
71 #include <opencv2/face.hpp>
72 namespace face = cv::face;
73 #else
74 namespace face = cv;
75 #endif
76 
77 // utility for resolving path
78 namespace boost
79 {
80 #if BOOST_VERSION < 105000
81 namespace filesystem3
82 { // for hydro
83 #else
84 namespace filesystem
85 {
86 #endif
87 template <>
88 path& path::append<typename path::iterator>(typename path::iterator lhs, typename path::iterator rhs,
89  const codecvt_type& cvt)
90 {
91  for (; lhs != rhs; ++lhs)
92  *this /= *lhs;
93  return *this;
94 }
95 path user_expanded_path(const path& p)
96 {
97  path::const_iterator it(p.begin());
98  std::string user_dir = (*it).string();
99  if (user_dir.length() == 0 || user_dir[0] != '~')
100  return p;
101  path ret;
102  char* homedir;
103  if (user_dir.length() == 1)
104  {
105  homedir = getenv("HOME");
106  if (homedir == nullptr)
107  {
108  homedir = getpwuid(getuid())->pw_dir;
109  }
110  }
111  else
112  {
113  std::string uname = user_dir.substr(1, user_dir.length());
114  passwd* pw = getpwnam(uname.c_str());
115  if (pw == nullptr)
116  return p;
117  homedir = pw->pw_dir;
118  }
119  ret = path(std::string(homedir));
120  return ret.append(++it, p.end(), path::codecvt());
121 }
122 } // namespace filesystem
123 } // namespace boost
124 
125 namespace opencv_apps
126 {
128 {
129  std::map<std::string, int> m_;
130 
131 public:
132  void add(std::vector<std::string>& l)
133  {
134  int id = 0;
135  for (std::map<std::string, int>::const_iterator it = m_.begin(); it != m_.end(); ++it)
136  {
137  if (id < it->second)
138  id = it->second + 1;
139  }
140  for (const std::string& i : l)
141  {
142  if (m_.find(i) == m_.end())
143  {
144  m_[i] = id;
145  id++;
146  }
147  }
148  }
149  std::vector<int> get(std::vector<std::string>& v)
150  {
151  std::vector<int> ret(v.size());
152  for (size_t i = 0; i < v.size(); ++i)
153  {
154  ret[i] = m_[v[i]];
155  }
156  return ret;
157  }
158  std::string lookup(int id)
159  {
160  for (std::map<std::string, int>::const_iterator it = m_.begin(); it != m_.end(); ++it)
161  {
162  if (it->second == id)
163  return it->first;
164  }
165  return "nan";
166  }
167  const std::map<std::string, int>& getMap() const
168  {
169  return m_;
170  }
171 
172  void debugPrint()
173  {
174  ROS_WARN_STREAM("label mapper: debug print:");
175  for (std::map<std::string, int>::const_iterator it = m_.begin(); it != m_.end(); ++it)
176  {
177  ROS_WARN_STREAM("\t" << it->first << ": " << it->second);
178  }
179  ROS_WARN_STREAM("label mapper: debug print end");
180  }
181 };
182 
183 class Storage
184 {
185  fs::path base_dir_;
186 
187 public:
188  Storage(const fs::path& base_dir)
189  {
190  base_dir_ = fs::user_expanded_path(base_dir);
191  if (!fs::exists(base_dir_))
192  {
193  init();
194  }
195  if (!fs::is_directory(base_dir_))
196  {
197  std::stringstream ss;
198  ss << base_dir_ << " is not a directory";
199  throw std::runtime_error(ss.str());
200  }
201  };
202  void init()
203  {
204  if (!fs::create_directories(base_dir_))
205  {
206  std::stringstream ss;
207  ss << "failed to initialize directory: " << base_dir_;
208  throw std::runtime_error(ss.str());
209  }
210  }
211 
212  void load(std::vector<cv::Mat>& images, std::vector<std::string>& labels, bool append = true)
213  {
214  if (!append)
215  {
216  images.clear();
217  labels.clear();
218  }
219  fs::directory_iterator end;
220  for (fs::directory_iterator it(base_dir_); it != end; ++it)
221  {
222  if (fs::is_directory(*it))
223  {
224  std::string label = it->path().stem().string();
225  for (fs::directory_iterator cit(it->path()); cit != end; ++cit)
226  {
227  if (fs::is_directory(*cit))
228  continue;
229  fs::path file_path = cit->path();
230  try
231  {
232  cv::Mat img = cv::imread(file_path.string(), CV_LOAD_IMAGE_COLOR);
233  labels.push_back(label);
234  images.push_back(img);
235  }
236  catch (cv::Exception& e)
237  {
238  ROS_ERROR_STREAM("Error: load image from " << file_path << ": " << e.what());
239  }
240  }
241  }
242  }
243  }
244 
245  void save(const std::vector<cv::Mat>& images, const std::vector<std::string>& labels)
246  {
247  if (images.size() != labels.size())
248  {
249  throw std::length_error("images.size() != labels.size()");
250  }
251  for (size_t i = 0; i < images.size(); ++i)
252  {
253  save(images[i], labels[i]);
254  }
255  }
256 
257  void save(const cv::Mat& image, const std::string& label)
258  {
259  fs::path img_dir = base_dir_ / fs::path(label);
260  if (!fs::exists(img_dir) && !fs::create_directories(img_dir))
261  {
262  std::stringstream ss;
263  ss << "failed to initialize directory: " << img_dir;
264  throw std::runtime_error(ss.str());
265  }
266  fs::directory_iterator end;
267  int file_count = 0;
268  for (fs::directory_iterator it(img_dir); it != end; ++it)
269  {
270  if (!fs::is_directory(*it))
271  file_count++;
272  }
273 
274  std::stringstream ss;
275  // data_dir/person_label/person_label_123456.jpg
276  ss << label << "_" << std::setw(6) << std::setfill('0') << file_count << ".jpg";
277  fs::path file_path = img_dir / ss.str();
278  ROS_INFO_STREAM("saving image to :" << file_path);
279  try
280  {
281  cv::imwrite(file_path.string(), image);
282  }
283  catch (cv::Exception& e)
284  {
285  ROS_ERROR_STREAM("Error: save image to " << file_path << ": " << e.what());
286  }
287  }
288 };
289 
291 {
292  typedef opencv_apps::FaceRecognitionConfig Config;
293  typedef dynamic_reconfigure::Server<Config> Server;
297 
298  Config config_;
308 
314  std::string data_dir_;
315  boost::mutex mutex_;
316 
320  cv::Ptr<face::FaceRecognizer> model_;
321 
322  void drawFace(cv::Mat& img, const opencv_apps::Face& face)
323  {
324  cv::Rect r(int(face.face.x - face.face.width / 2.0 - face.face.width * face_padding_ / 2.0),
325  int(face.face.y - face.face.height / 2.0 - face.face.height * face_padding_ / 2.0),
326  int(face.face.width + face.face.width * face_padding_),
327  int(face.face.height + face.face.height * face_padding_));
328  cv::Scalar color(0.0, 0.0, 255.0);
329  int boldness = 2;
330  cv::rectangle(img, r.tl(), r.br(), color, boldness, CV_AA);
331 
332  double font_scale = 1.5;
333  int text_height = 20;
334  cv::Point text_bl;
335  if (r.br().y + text_height > img.rows)
336  text_bl = r.tl() + cv::Point(0, -text_height);
337  else
338  text_bl = r.br() + cv::Point(-r.width, text_height);
339  std::stringstream ss;
340  ss << face.label << " (" << std::fixed << std::setprecision(2) << face.confidence << ")";
341  cv::putText(img, ss.str(), text_bl, cv::FONT_HERSHEY_PLAIN, font_scale, color, boldness, CV_AA);
342  }
343 
344  void extractImage(const cv::Mat& img, const opencv_apps::Rect& rect, cv::Mat& ret, double padding = 0.0)
345  {
346  int x = std::max(0, int(rect.x - rect.width / 2.0 - rect.width * padding / 2.0));
347  int y = std::max(0, int(rect.y - rect.height / 2.0 - rect.height * padding / 2.0));
348  cv::Rect r(x, y, std::min(img.cols - x, int(rect.width + rect.width * padding)),
349  std::min(img.rows - y, int(rect.height + rect.height * padding)));
350  ret = img(r);
351  }
352 
353  void extractImage(const cv::Mat& img, const opencv_apps::Face& face, cv::Mat& ret, double padding = 0.0)
354  {
355  extractImage(img, face.face, ret, padding);
356  }
357 
358  void retrain()
359  {
360  NODELET_DEBUG("retrain");
361  std::vector<cv::Mat> images;
362  std::vector<std::string> labels;
363  train(images, labels);
364  }
365 
366  void train(std::vector<cv::Mat>& images, std::vector<std::string>& labels)
367  {
368  size_t new_image_size = images.size();
369 
370  if (use_saved_data_)
371  {
372  storage_->load(images, labels);
373  }
374 
375  if (images.empty())
376  return;
377 
378  std::vector<cv::Mat> resized_images(images.size());
379  for (int i = 0; i < images.size(); ++i)
380  {
381  cv::resize(images[i], resized_images[i], face_model_size_, 0, 0, cv::INTER_CUBIC);
382  cv::cvtColor(resized_images[i], resized_images[i], CV_BGR2GRAY);
383  }
384 
385  label_mapper_->add(labels);
386  std::vector<int> ids = label_mapper_->get(labels);
387  NODELET_INFO_STREAM("training with " << images.size() << " images");
388  // label_mapper_->debugPrint();
389  model_->train(resized_images, ids);
390 
391  if (save_train_data_ && new_image_size > 0)
392  {
393  std::vector<cv::Mat> new_images(images.begin(), images.begin() + new_image_size);
394  std::vector<std::string> new_labels(labels.begin(), labels.begin() + new_image_size);
395  storage_->save(new_images, new_labels);
396  }
397  }
398 
399  void predict(const cv::Mat& img, int& label, double& confidence)
400  {
401  cv::Mat resized_img;
402  cv::resize(img, resized_img, face_model_size_, 0, 0, cv::INTER_CUBIC);
403  cv::cvtColor(resized_img, resized_img, CV_BGR2GRAY);
404  model_->predict(resized_img, label, confidence);
405  }
406 
407  void faceImageCallback(const sensor_msgs::Image::ConstPtr& image,
408  const opencv_apps::FaceArrayStamped::ConstPtr& faces)
409  {
410  NODELET_DEBUG("faceImageCallback");
411  boost::mutex::scoped_lock lock(mutex_);
412 
413  // check if the face data is being trained
414  if (label_mapper_->getMap().empty())
415  {
416  NODELET_WARN_THROTTLE(1.0, "Face data is not trained. Please train first.");
417  return;
418  }
419 
420  // check if need to draw and publish debug image
421  bool publish_debug_image = debug_img_pub_.getNumSubscribers() > 0;
422 
423  try
424  {
425  cv::Mat cv_img = cv_bridge::toCvShare(image, enc::BGR8)->image;
426  opencv_apps::FaceArrayStamped ret_msg = *faces;
427  for (size_t i = 0; i < faces->faces.size(); ++i)
428  {
429  cv::Mat face_img, resized_image;
430  extractImage(cv_img, faces->faces[i], face_img, face_padding_);
431 
432  int label_id = -1;
433  double confidence = 0.0;
434  predict(face_img, label_id, confidence);
435  if (label_id == -1)
436  continue;
437  ret_msg.faces[i].label = label_mapper_->lookup(label_id);
438  ret_msg.faces[i].confidence = confidence;
439 
440  // draw debug image
441  if (publish_debug_image)
442  drawFace(cv_img, ret_msg.faces[i]);
443  }
444  face_pub_.publish(ret_msg);
445  if (publish_debug_image)
446  {
447  sensor_msgs::Image::Ptr debug_img = cv_bridge::CvImage(image->header, enc::BGR8, cv_img).toImageMsg();
448  debug_img_pub_.publish(debug_img);
449  NODELET_DEBUG("Published debug image");
450  }
451  }
452  catch (cv::Exception& e)
453  {
454  NODELET_ERROR_STREAM("error at image processing: " << e.err << " " << e.func << " " << e.file << " " << e.line);
455  }
456  }
457 
458  bool trainCallback(opencv_apps::FaceRecognitionTrain::Request& req, opencv_apps::FaceRecognitionTrain::Response& res)
459  {
460  boost::mutex::scoped_lock lock(mutex_);
461  try
462  {
463  std::vector<cv::Mat> images(req.images.size());
464  bool use_roi = !req.rects.empty();
465 
466  if (use_roi && req.images.size() != req.rects.size())
467  {
468  throw std::length_error("req.images.size() != req.rects.size()");
469  }
470 
471  for (size_t i = 0; i < req.images.size(); ++i)
472  {
473  sensor_msgs::Image img = req.images[i];
474  images[i] = cv_bridge::toCvCopy(img, enc::BGR8)->image;
475  if (use_roi)
476  {
477  cv::Mat face_img;
478  extractImage(images[i], req.rects[i], face_img);
479  images[i] = face_img;
480  }
481  }
482  std::vector<std::string> labels(req.labels.begin(), req.labels.end());
483  train(images, labels);
484  res.ok = true;
485  return true;
486  }
487  catch (cv::Exception& e)
488  {
489  std::stringstream ss;
490  ss << "error at training: " << e.err << " " << e.func << " " << e.file << " " << e.line;
491  res.ok = false;
492  res.error = ss.str();
493  }
494  return false;
495  }
496 
497  void configCallback(Config& config, uint32_t level)
498  {
499  boost::mutex::scoped_lock lock(mutex_);
500 
501  bool need_recreate_model = false;
502  bool need_retrain = false;
503 
504  use_saved_data_ = config.use_saved_data;
505  save_train_data_ = config.save_train_data;
506  face_padding_ = config.face_padding;
507 
508  if (face_model_size_.width != config.face_model_width)
509  {
510  face_model_size_.width = config.face_model_width;
511  need_retrain = true;
512  }
513  if (face_model_size_.height != config.face_model_height)
514  {
515  face_model_size_.height = config.face_model_height;
516  need_retrain = true;
517  }
518 
519  if (data_dir_ != config.data_dir)
520  {
521  data_dir_ = config.data_dir;
522  need_retrain = true;
523  label_mapper_.reset(new LabelMapper());
524  storage_.reset(new Storage(fs::path(data_dir_)));
525  }
526 
527  if (config_.model_method != config.model_method)
528  {
529  need_recreate_model = true;
530  }
531 
532  if (config_.model_num_components != config.model_num_components)
533  {
534  need_recreate_model = true;
535  }
536 
537  if (config.model_method == "LBPH" &&
538  (config_.lbph_radius != config.lbph_radius || config_.lbph_neighbors != config.lbph_neighbors ||
539  config_.lbph_grid_x != config.lbph_grid_x || config_.lbph_grid_y != config.lbph_grid_y))
540  {
541  need_recreate_model = true;
542  }
543 
544  if (need_recreate_model)
545  {
546  try
547  {
548  if (config.model_method == "eigen")
549  {
550 // https://docs.opencv.org/3.3.1/da/d60/tutorial_face_main.html
551 #if CV_MAJOR_VERSION >= 3 && CV_MINOR_VERSION >= 3
552  model_ = face::EigenFaceRecognizer::create(config.model_num_components, config.model_threshold);
553 #else
554  model_ = face::createEigenFaceRecognizer(config.model_num_components, config.model_threshold);
555 #endif
556  }
557  else if (config.model_method == "fisher")
558  {
559 #if CV_MAJOR_VERSION >= 3 && CV_MINOR_VERSION >= 3
560  model_ = face::FisherFaceRecognizer::create(config.model_num_components, config.model_threshold);
561 #else
562  model_ = face::createFisherFaceRecognizer(config.model_num_components, config.model_threshold);
563 #endif
564  }
565  else if (config.model_method == "LBPH")
566  {
567 #if CV_MAJOR_VERSION >= 3 && CV_MINOR_VERSION >= 3
568  model_ = face::LBPHFaceRecognizer::create(config.lbph_radius, config.lbph_neighbors, config.lbph_grid_x,
569  config.lbph_grid_y);
570 #else
571  model_ = face::createLBPHFaceRecognizer(config.lbph_radius, config.lbph_neighbors, config.lbph_grid_x,
572  config.lbph_grid_y);
573 #endif
574  }
575  need_retrain = true;
576  }
577  catch (cv::Exception& e)
578  {
579  NODELET_ERROR_STREAM("Error: create face recognizer: " << e.what());
580  }
581  }
582 
583  if (need_retrain)
584  {
585  try
586  {
587  retrain();
588  }
589  catch (cv::Exception& e)
590  {
591  NODELET_ERROR_STREAM("Error: train: " << e.what());
592  }
593  }
594 
595  if (config_.model_threshold != config.model_threshold)
596  {
597  try
598  {
599 #if CV_MAJOR_VERSION >= 3
600  if (face::BasicFaceRecognizer* model = dynamic_cast<face::BasicFaceRecognizer*>(model_.get()))
601  {
602  model->setThreshold(config.model_threshold);
603  }
604  else if (face::LBPHFaceRecognizer* model = dynamic_cast<face::LBPHFaceRecognizer*>(model_.get()))
605  {
606  model->setThreshold(config.model_threshold);
607  }
608 #else
609  model_->set("threshold", config.model_threshold);
610 #endif
611  }
612  catch (cv::Exception& e)
613  {
614  NODELET_ERROR_STREAM("Error: set threshold: " << e.what());
615  }
616  }
617  config_ = config;
618  }
619 
620  void subscribe() // NOLINT(modernize-use-override)
621  {
622  NODELET_DEBUG("subscribe");
623  img_sub_.subscribe(*it_, "image", 1);
624  face_sub_.subscribe(*nh_, "faces", 1);
625  if (use_async_)
626  {
627  async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> >(queue_size_);
628  async_->connectInput(img_sub_, face_sub_);
629  async_->registerCallback(boost::bind(&FaceRecognitionNodelet::faceImageCallback, this, _1, _2));
630  }
631  else
632  {
633  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(queue_size_);
634  sync_->connectInput(img_sub_, face_sub_);
635  sync_->registerCallback(boost::bind(&FaceRecognitionNodelet::faceImageCallback, this, _1, _2));
636  }
637  }
638 
639  void unsubscribe() // NOLINT(modernize-use-override)
640  {
641  NODELET_DEBUG("unsubscribe");
642  img_sub_.unsubscribe();
643  face_sub_.unsubscribe();
644  }
645 
646 public:
647  virtual void onInit() // NOLINT(modernize-use-override)
648  {
649  Nodelet::onInit();
650 
651  // variables
652  face_model_size_ = cv::Size(190, 90);
653 
654  // dynamic reconfigures
655  cfg_srv_ = boost::make_shared<Server>(*pnh_);
656  Server::CallbackType f = boost::bind(&FaceRecognitionNodelet::configCallback, this, _1, _2);
657  cfg_srv_->setCallback(f);
658 
659  // parameters
660  pnh_->param("approximate_sync", use_async_, false);
661  pnh_->param("queue_size", queue_size_, 100);
662 
663  // advertise
664  debug_img_pub_ = advertise<sensor_msgs::Image>(*pnh_, "debug_image", 1);
665  face_pub_ = advertise<opencv_apps::FaceArrayStamped>(*pnh_, "output", 1);
666  train_srv_ = pnh_->advertiseService("train", &FaceRecognitionNodelet::trainCallback, this);
668 
669  onInitPostProcess();
670  }
671 };
672 } // namespace opencv_apps
673 
675 {
677 {
678 public:
679  virtual void onInit() // NOLINT(modernize-use-override)
680  {
681  ROS_WARN("DeprecationWarning: Nodelet face_recognition/face_recognition is deprecated, "
682  "and renamed to opencv_apps/face_recognition.");
684  }
685 };
686 } // namespace face_recognition
687 
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
#define NODELET_INFO_STREAM(...)
const std::map< std::string, int > & getMap() const
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
void configCallback(Config &config, uint32_t level)
opencv_apps::FaceRecognitionConfig Config
void publish(const boost::shared_ptr< M > &message) const
f
Nodelet to automatically subscribe/unsubscribe topics according to subscription of advertised topics...
Definition: nodelet.h:70
boost::shared_ptr< LabelMapper > label_mapper_
Demo code to calculate moments.
Definition: nodelet.h:48
void add(std::vector< std::string > &l)
void train(std::vector< cv::Mat > &images, std::vector< std::string > &labels)
bool trainCallback(opencv_apps::FaceRecognitionTrain::Request &req, opencv_apps::FaceRecognitionTrain::Response &res)
void drawFace(cv::Mat &img, const opencv_apps::Face &face)
#define ROS_WARN(...)
void load(std::vector< cv::Mat > &images, std::vector< std::string > &labels, bool append=true)
message_filters::sync_policies::ExactTime< sensor_msgs::Image, opencv_apps::FaceArrayStamped > SyncPolicy
void faceImageCallback(const sensor_msgs::Image::ConstPtr &image, const opencv_apps::FaceArrayStamped::ConstPtr &faces)
Storage(const fs::path &base_dir)
#define NODELET_ERROR_STREAM(...)
PLUGINLIB_EXPORT_CLASS(opencv_apps::FaceRecognitionNodelet, nodelet::Nodelet)
std::map< std::string, int > m_
cv::Ptr< face::FaceRecognizer > model_
void subscribe()
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method...
void save(const cv::Mat &image, const std::string &label)
#define NODELET_WARN_THROTTLE(rate,...)
image_transport::SubscriberFilter img_sub_
path user_expanded_path(const path &p)
void unsubscribe()
This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this me...
message_filters::Subscriber< opencv_apps::FaceArrayStamped > face_sub_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
void extractImage(const cv::Mat &img, const opencv_apps::Face &face, cv::Mat &ret, double padding=0.0)
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, opencv_apps::FaceArrayStamped > ApproximateSyncPolicy
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_
#define ROS_WARN_STREAM(args)
void subscribe(ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const TransportHints &transport_hints=TransportHints())
uint32_t getNumSubscribers() const
#define ROS_INFO_STREAM(args)
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)
ROSCPP_DECL std::string append(const std::string &left, const std::string &right)
#define ROS_ERROR_STREAM(args)
boost::shared_ptr< image_transport::ImageTransport > it_
dynamic_reconfigure::Server< Config > Server
void predict(const cv::Mat &img, int &label, double &confidence)
#define NODELET_DEBUG(...)
sensor_msgs::ImagePtr toImageMsg() const
void extractImage(const cv::Mat &img, const opencv_apps::Rect &rect, cv::Mat &ret, double padding=0.0)
void save(const std::vector< cv::Mat > &images, const std::vector< std::string > &labels)


opencv_apps
Author(s): Kei Okada
autogenerated on Wed Apr 24 2019 03:00:17