face_recognition_nodelet.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2017, Yuki Furuta.
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Kei Okada nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00035 #include <algorithm>
00036 #include <boost/filesystem.hpp>
00037 #include <boost/shared_ptr.hpp>
00038 #include <boost/thread.hpp>
00039 #include <boost/version.hpp>
00040 #include <iomanip>
00041 #include <map>
00042 #include <stdexcept>
00043 #include <string>
00044 #include <opencv2/opencv.hpp>
00045 #include <pwd.h>
00046 #include <vector>
00047 
00048 #include <cv_bridge/cv_bridge.h>
00049 #include <dynamic_reconfigure/server.h>
00050 #include <image_transport/image_transport.h>
00051 #include <image_transport/subscriber_filter.h>
00052 #include <message_filters/subscriber.h>
00053 #include <message_filters/synchronizer.h>
00054 #include <message_filters/sync_policies/approximate_time.h>
00055 #include <message_filters/sync_policies/exact_time.h>
00056 #include <sensor_msgs/image_encodings.h>
00057 
00058 #include <opencv_apps/nodelet.h>
00059 #include <opencv_apps/FaceArrayStamped.h>
00060 #include <opencv_apps/FaceRecognitionTrain.h>
00061 #include <opencv_apps/FaceRecognitionConfig.h>
00062 
00063 namespace enc = sensor_msgs::image_encodings;
00064 #if BOOST_VERSION < 105000
00065 namespace fs = boost::filesystem3;  // for hydro
00066 #else
00067 namespace fs = boost::filesystem;
00068 #endif
00069 
00070 #if CV_MAJOR_VERSION >= 3
00071 #include <opencv2/face.hpp>
00072 namespace face = cv::face;
00073 #else
00074 namespace face = cv;
00075 #endif
00076 
00077 // utility for resolving path
00078 namespace boost
00079 {
00080 #if BOOST_VERSION < 105000
00081 namespace filesystem3
00082 {  // for hydro
00083 #else
00084 namespace filesystem
00085 {
00086 #endif
00087 template <>
00088 path& path::append<typename path::iterator>(typename path::iterator lhs, typename path::iterator rhs,
00089                                             const codecvt_type& cvt)
00090 {
00091   for (; lhs != rhs; ++lhs)
00092     *this /= *lhs;
00093   return *this;
00094 }
00095 path user_expanded_path(const path& p)
00096 {
00097   path::const_iterator it(p.begin());
00098   std::string user_dir = (*it).string();
00099   if (user_dir.length() == 0 || user_dir[0] != '~')
00100     return p;
00101   path ret;
00102   char* homedir;
00103   if (user_dir.length() == 1)
00104   {
00105     homedir = getenv("HOME");
00106     if (homedir == nullptr)
00107     {
00108       homedir = getpwuid(getuid())->pw_dir;
00109     }
00110   }
00111   else
00112   {
00113     std::string uname = user_dir.substr(1, user_dir.length());
00114     passwd* pw = getpwnam(uname.c_str());
00115     if (pw == nullptr)
00116       return p;
00117     homedir = pw->pw_dir;
00118   }
00119   ret = path(std::string(homedir));
00120   return ret.append(++it, p.end(), path::codecvt());
00121 }
00122 }  // namespace filesystem
00123 }  // namespace boost
00124 
00125 namespace opencv_apps
00126 {
00127 class LabelMapper
00128 {
00129   std::map<std::string, int> m_;
00130 
00131 public:
00132   void add(std::vector<std::string>& l)
00133   {
00134     int id = 0;
00135     for (std::map<std::string, int>::const_iterator it = m_.begin(); it != m_.end(); ++it)
00136     {
00137       if (id < it->second)
00138         id = it->second + 1;
00139     }
00140     for (const std::string& i : l)
00141     {
00142       if (m_.find(i) == m_.end())
00143       {
00144         m_[i] = id;
00145         id++;
00146       }
00147     }
00148   }
00149   std::vector<int> get(std::vector<std::string>& v)
00150   {
00151     std::vector<int> ret(v.size());
00152     for (size_t i = 0; i < v.size(); ++i)
00153     {
00154       ret[i] = m_[v[i]];
00155     }
00156     return ret;
00157   }
00158   std::string lookup(int id)
00159   {
00160     for (std::map<std::string, int>::const_iterator it = m_.begin(); it != m_.end(); ++it)
00161     {
00162       if (it->second == id)
00163         return it->first;
00164     }
00165     return "nan";
00166   }
00167   const std::map<std::string, int>& getMap() const
00168   {
00169     return m_;
00170   }
00171 
00172   void debugPrint()
00173   {
00174     ROS_WARN_STREAM("label mapper: debug print:");
00175     for (std::map<std::string, int>::const_iterator it = m_.begin(); it != m_.end(); ++it)
00176     {
00177       ROS_WARN_STREAM("\t" << it->first << ": " << it->second);
00178     }
00179     ROS_WARN_STREAM("label mapper: debug print end");
00180   }
00181 };
00182 
00183 class Storage
00184 {
00185   fs::path base_dir_;
00186 
00187 public:
00188   Storage(const fs::path& base_dir)
00189   {
00190     base_dir_ = fs::user_expanded_path(base_dir);
00191     if (!fs::exists(base_dir_))
00192     {
00193       init();
00194     }
00195     if (!fs::is_directory(base_dir_))
00196     {
00197       std::stringstream ss;
00198       ss << base_dir_ << " is not a directory";
00199       throw std::runtime_error(ss.str());
00200     }
00201   };
00202   void init()
00203   {
00204     if (!fs::create_directories(base_dir_))
00205     {
00206       std::stringstream ss;
00207       ss << "failed to initialize directory: " << base_dir_;
00208       throw std::runtime_error(ss.str());
00209     }
00210   }
00211 
00212   void load(std::vector<cv::Mat>& images, std::vector<std::string>& labels, bool append = true)
00213   {
00214     if (!append)
00215     {
00216       images.clear();
00217       labels.clear();
00218     }
00219     fs::directory_iterator end;
00220     for (fs::directory_iterator it(base_dir_); it != end; ++it)
00221     {
00222       if (fs::is_directory(*it))
00223       {
00224         std::string label = it->path().stem().string();
00225         for (fs::directory_iterator cit(it->path()); cit != end; ++cit)
00226         {
00227           if (fs::is_directory(*cit))
00228             continue;
00229           fs::path file_path = cit->path();
00230           try
00231           {
00232             cv::Mat img = cv::imread(file_path.string(), CV_LOAD_IMAGE_COLOR);
00233             labels.push_back(label);
00234             images.push_back(img);
00235           }
00236           catch (cv::Exception& e)
00237           {
00238             ROS_ERROR_STREAM("Error: load image from " << file_path << ": " << e.what());
00239           }
00240         }
00241       }
00242     }
00243   }
00244 
00245   void save(const std::vector<cv::Mat>& images, const std::vector<std::string>& labels)
00246   {
00247     if (images.size() != labels.size())
00248     {
00249       throw std::length_error("images.size() != labels.size()");
00250     }
00251     for (size_t i = 0; i < images.size(); ++i)
00252     {
00253       save(images[i], labels[i]);
00254     }
00255   }
00256 
00257   void save(const cv::Mat& image, const std::string& label)
00258   {
00259     fs::path img_dir = base_dir_ / fs::path(label);
00260     if (!fs::exists(img_dir) && !fs::create_directories(img_dir))
00261     {
00262       std::stringstream ss;
00263       ss << "failed to initialize directory: " << img_dir;
00264       throw std::runtime_error(ss.str());
00265     }
00266     fs::directory_iterator end;
00267     int file_count = 0;
00268     for (fs::directory_iterator it(img_dir); it != end; ++it)
00269     {
00270       if (!fs::is_directory(*it))
00271         file_count++;
00272     }
00273 
00274     std::stringstream ss;
00275     // data_dir/person_label/person_label_123456.jpg
00276     ss << label << "_" << std::setw(6) << std::setfill('0') << file_count << ".jpg";
00277     fs::path file_path = img_dir / ss.str();
00278     ROS_INFO_STREAM("saving image to :" << file_path);
00279     try
00280     {
00281       cv::imwrite(file_path.string(), image);
00282     }
00283     catch (cv::Exception& e)
00284     {
00285       ROS_ERROR_STREAM("Error: save image to " << file_path << ": " << e.what());
00286     }
00287   }
00288 };
00289 
00290 class FaceRecognitionNodelet : public opencv_apps::Nodelet
00291 {
00292   typedef opencv_apps::FaceRecognitionConfig Config;
00293   typedef dynamic_reconfigure::Server<Config> Server;
00294   typedef message_filters::sync_policies::ExactTime<sensor_msgs::Image, opencv_apps::FaceArrayStamped> SyncPolicy;
00295   typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, opencv_apps::FaceArrayStamped>
00296       ApproximateSyncPolicy;
00297 
00298   Config config_;
00299   boost::shared_ptr<Server> cfg_srv_;
00300   boost::shared_ptr<image_transport::ImageTransport> it_;
00301   boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > sync_;
00302   boost::shared_ptr<message_filters::Synchronizer<ApproximateSyncPolicy> > async_;
00303   image_transport::SubscriberFilter img_sub_;
00304   message_filters::Subscriber<opencv_apps::FaceArrayStamped> face_sub_;
00305   ros::Publisher debug_img_pub_;
00306   ros::Publisher face_pub_;
00307   ros::ServiceServer train_srv_;
00308 
00309   bool save_train_data_;
00310   bool use_async_;
00311   bool use_saved_data_;
00312   double face_padding_;
00313   int queue_size_;
00314   std::string data_dir_;
00315   boost::mutex mutex_;
00316 
00317   boost::shared_ptr<LabelMapper> label_mapper_;
00318   boost::shared_ptr<Storage> storage_;
00319   cv::Size face_model_size_;
00320   cv::Ptr<face::FaceRecognizer> model_;
00321 
00322   void drawFace(cv::Mat& img, const opencv_apps::Face& face)
00323   {
00324     cv::Rect r(int(face.face.x - face.face.width / 2.0 - face.face.width * face_padding_ / 2.0),
00325                int(face.face.y - face.face.height / 2.0 - face.face.height * face_padding_ / 2.0),
00326                int(face.face.width + face.face.width * face_padding_),
00327                int(face.face.height + face.face.height * face_padding_));
00328     cv::Scalar color(0.0, 0.0, 255.0);
00329     int boldness = 2;
00330     cv::rectangle(img, r.tl(), r.br(), color, boldness, CV_AA);
00331 
00332     double font_scale = 1.5;
00333     int text_height = 20;
00334     cv::Point text_bl;
00335     if (r.br().y + text_height > img.rows)
00336       text_bl = r.tl() + cv::Point(0, -text_height);
00337     else
00338       text_bl = r.br() + cv::Point(-r.width, text_height);
00339     std::stringstream ss;
00340     ss << face.label << " (" << std::fixed << std::setprecision(2) << face.confidence << ")";
00341     cv::putText(img, ss.str(), text_bl, cv::FONT_HERSHEY_PLAIN, font_scale, color, boldness, CV_AA);
00342   }
00343 
00344   void extractImage(const cv::Mat& img, const opencv_apps::Rect& rect, cv::Mat& ret, double padding = 0.0)
00345   {
00346     int x = std::max(0, int(rect.x - rect.width / 2.0 - rect.width * padding / 2.0));
00347     int y = std::max(0, int(rect.y - rect.height / 2.0 - rect.height * padding / 2.0));
00348     cv::Rect r(x, y, std::min(img.cols - x, int(rect.width + rect.width * padding)),
00349                std::min(img.rows - y, int(rect.height + rect.height * padding)));
00350     ret = img(r);
00351   }
00352 
00353   void extractImage(const cv::Mat& img, const opencv_apps::Face& face, cv::Mat& ret, double padding = 0.0)
00354   {
00355     extractImage(img, face.face, ret, padding);
00356   }
00357 
00358   void retrain()
00359   {
00360     NODELET_DEBUG("retrain");
00361     std::vector<cv::Mat> images;
00362     std::vector<std::string> labels;
00363     train(images, labels);
00364   }
00365 
00366   void train(std::vector<cv::Mat>& images, std::vector<std::string>& labels)
00367   {
00368     size_t new_image_size = images.size();
00369 
00370     if (use_saved_data_)
00371     {
00372       storage_->load(images, labels);
00373     }
00374 
00375     if (images.empty())
00376       return;
00377 
00378     std::vector<cv::Mat> resized_images(images.size());
00379     for (int i = 0; i < images.size(); ++i)
00380     {
00381       cv::resize(images[i], resized_images[i], face_model_size_, 0, 0, cv::INTER_CUBIC);
00382       cv::cvtColor(resized_images[i], resized_images[i], CV_BGR2GRAY);
00383     }
00384 
00385     label_mapper_->add(labels);
00386     std::vector<int> ids = label_mapper_->get(labels);
00387     NODELET_INFO_STREAM("training with " << images.size() << " images");
00388     // label_mapper_->debugPrint();
00389     model_->train(resized_images, ids);
00390 
00391     if (save_train_data_ && new_image_size > 0)
00392     {
00393       std::vector<cv::Mat> new_images(images.begin(), images.begin() + new_image_size);
00394       std::vector<std::string> new_labels(labels.begin(), labels.begin() + new_image_size);
00395       storage_->save(new_images, new_labels);
00396     }
00397   }
00398 
00399   void predict(const cv::Mat& img, int& label, double& confidence)
00400   {
00401     cv::Mat resized_img;
00402     cv::resize(img, resized_img, face_model_size_, 0, 0, cv::INTER_CUBIC);
00403     cv::cvtColor(resized_img, resized_img, CV_BGR2GRAY);
00404     model_->predict(resized_img, label, confidence);
00405   }
00406 
00407   void faceImageCallback(const sensor_msgs::Image::ConstPtr& image,
00408                          const opencv_apps::FaceArrayStamped::ConstPtr& faces)
00409   {
00410     NODELET_DEBUG("faceImageCallback");
00411     boost::mutex::scoped_lock lock(mutex_);
00412 
00413     // check if the face data is being trained
00414     if (label_mapper_->getMap().empty())
00415     {
00416       NODELET_WARN_THROTTLE(1.0, "Face data is not trained. Please train first.");
00417       return;
00418     }
00419 
00420     // check if need to draw and publish debug image
00421     bool publish_debug_image = debug_img_pub_.getNumSubscribers() > 0;
00422 
00423     try
00424     {
00425       cv::Mat cv_img = cv_bridge::toCvShare(image, enc::BGR8)->image;
00426       opencv_apps::FaceArrayStamped ret_msg = *faces;
00427       for (size_t i = 0; i < faces->faces.size(); ++i)
00428       {
00429         cv::Mat face_img, resized_image;
00430         extractImage(cv_img, faces->faces[i], face_img, face_padding_);
00431 
00432         int label_id = -1;
00433         double confidence = 0.0;
00434         predict(face_img, label_id, confidence);
00435         if (label_id == -1)
00436           continue;
00437         ret_msg.faces[i].label = label_mapper_->lookup(label_id);
00438         ret_msg.faces[i].confidence = confidence;
00439 
00440         // draw debug image
00441         if (publish_debug_image)
00442           drawFace(cv_img, ret_msg.faces[i]);
00443       }
00444       face_pub_.publish(ret_msg);
00445       if (publish_debug_image)
00446       {
00447         sensor_msgs::Image::Ptr debug_img = cv_bridge::CvImage(image->header, enc::BGR8, cv_img).toImageMsg();
00448         debug_img_pub_.publish(debug_img);
00449         NODELET_DEBUG("Published debug image");
00450       }
00451     }
00452     catch (cv::Exception& e)
00453     {
00454       NODELET_ERROR_STREAM("error at image processing: " << e.err << " " << e.func << " " << e.file << " " << e.line);
00455     }
00456   }
00457 
00458   bool trainCallback(opencv_apps::FaceRecognitionTrain::Request& req, opencv_apps::FaceRecognitionTrain::Response& res)
00459   {
00460     boost::mutex::scoped_lock lock(mutex_);
00461     try
00462     {
00463       std::vector<cv::Mat> images(req.images.size());
00464       bool use_roi = !req.rects.empty();
00465 
00466       if (use_roi && req.images.size() != req.rects.size())
00467       {
00468         throw std::length_error("req.images.size() != req.rects.size()");
00469       }
00470 
00471       for (size_t i = 0; i < req.images.size(); ++i)
00472       {
00473         sensor_msgs::Image img = req.images[i];
00474         images[i] = cv_bridge::toCvCopy(img, enc::BGR8)->image;
00475         if (use_roi)
00476         {
00477           cv::Mat face_img;
00478           extractImage(images[i], req.rects[i], face_img);
00479           images[i] = face_img;
00480         }
00481       }
00482       std::vector<std::string> labels(req.labels.begin(), req.labels.end());
00483       train(images, labels);
00484       res.ok = true;
00485       return true;
00486     }
00487     catch (cv::Exception& e)
00488     {
00489       std::stringstream ss;
00490       ss << "error at training: " << e.err << " " << e.func << " " << e.file << " " << e.line;
00491       res.ok = false;
00492       res.error = ss.str();
00493     }
00494     return false;
00495   }
00496 
00497   void configCallback(Config& config, uint32_t level)
00498   {
00499     boost::mutex::scoped_lock lock(mutex_);
00500 
00501     bool need_recreate_model = false;
00502     bool need_retrain = false;
00503 
00504     use_saved_data_ = config.use_saved_data;
00505     save_train_data_ = config.save_train_data;
00506     face_padding_ = config.face_padding;
00507 
00508     if (face_model_size_.width != config.face_model_width)
00509     {
00510       face_model_size_.width = config.face_model_width;
00511       need_retrain = true;
00512     }
00513     if (face_model_size_.height != config.face_model_height)
00514     {
00515       face_model_size_.height = config.face_model_height;
00516       need_retrain = true;
00517     }
00518 
00519     if (data_dir_ != config.data_dir)
00520     {
00521       data_dir_ = config.data_dir;
00522       need_retrain = true;
00523       label_mapper_.reset(new LabelMapper());
00524       storage_.reset(new Storage(fs::path(data_dir_)));
00525     }
00526 
00527     if (config_.model_method != config.model_method)
00528     {
00529       need_recreate_model = true;
00530     }
00531 
00532     if (config_.model_num_components != config.model_num_components)
00533     {
00534       need_recreate_model = true;
00535     }
00536 
00537     if (config.model_method == "LBPH" &&
00538         (config_.lbph_radius != config.lbph_radius || config_.lbph_neighbors != config.lbph_neighbors ||
00539          config_.lbph_grid_x != config.lbph_grid_x || config_.lbph_grid_y != config.lbph_grid_y))
00540     {
00541       need_recreate_model = true;
00542     }
00543 
00544     if (need_recreate_model)
00545     {
00546       try
00547       {
00548         if (config.model_method == "eigen")
00549         {
00550 // https://docs.opencv.org/3.3.1/da/d60/tutorial_face_main.html
00551 #if CV_MAJOR_VERSION >= 3 && CV_MINOR_VERSION >= 3
00552           model_ = face::EigenFaceRecognizer::create(config.model_num_components, config.model_threshold);
00553 #else
00554           model_ = face::createEigenFaceRecognizer(config.model_num_components, config.model_threshold);
00555 #endif
00556         }
00557         else if (config.model_method == "fisher")
00558         {
00559 #if CV_MAJOR_VERSION >= 3 && CV_MINOR_VERSION >= 3
00560           model_ = face::FisherFaceRecognizer::create(config.model_num_components, config.model_threshold);
00561 #else
00562           model_ = face::createFisherFaceRecognizer(config.model_num_components, config.model_threshold);
00563 #endif
00564         }
00565         else if (config.model_method == "LBPH")
00566         {
00567 #if CV_MAJOR_VERSION >= 3 && CV_MINOR_VERSION >= 3
00568           model_ = face::LBPHFaceRecognizer::create(config.lbph_radius, config.lbph_neighbors, config.lbph_grid_x,
00569                                                     config.lbph_grid_y);
00570 #else
00571           model_ = face::createLBPHFaceRecognizer(config.lbph_radius, config.lbph_neighbors, config.lbph_grid_x,
00572                                                   config.lbph_grid_y);
00573 #endif
00574         }
00575         need_retrain = true;
00576       }
00577       catch (cv::Exception& e)
00578       {
00579         NODELET_ERROR_STREAM("Error: create face recognizer: " << e.what());
00580       }
00581     }
00582 
00583     if (need_retrain)
00584     {
00585       try
00586       {
00587         retrain();
00588       }
00589       catch (cv::Exception& e)
00590       {
00591         NODELET_ERROR_STREAM("Error: train: " << e.what());
00592       }
00593     }
00594 
00595     if (config_.model_threshold != config.model_threshold)
00596     {
00597       try
00598       {
00599 #if CV_MAJOR_VERSION >= 3
00600         if (face::BasicFaceRecognizer* model = dynamic_cast<face::BasicFaceRecognizer*>(model_.get()))
00601         {
00602           model->setThreshold(config.model_threshold);
00603         }
00604         else if (face::LBPHFaceRecognizer* model = dynamic_cast<face::LBPHFaceRecognizer*>(model_.get()))
00605         {
00606           model->setThreshold(config.model_threshold);
00607         }
00608 #else
00609         model_->set("threshold", config.model_threshold);
00610 #endif
00611       }
00612       catch (cv::Exception& e)
00613       {
00614         NODELET_ERROR_STREAM("Error: set threshold: " << e.what());
00615       }
00616     }
00617     config_ = config;
00618   }
00619 
00620   void subscribe()  // NOLINT(modernize-use-override)
00621   {
00622     NODELET_DEBUG("subscribe");
00623     img_sub_.subscribe(*it_, "image", 1);
00624     face_sub_.subscribe(*nh_, "faces", 1);
00625     if (use_async_)
00626     {
00627       async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> >(queue_size_);
00628       async_->connectInput(img_sub_, face_sub_);
00629       async_->registerCallback(boost::bind(&FaceRecognitionNodelet::faceImageCallback, this, _1, _2));
00630     }
00631     else
00632     {
00633       sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(queue_size_);
00634       sync_->connectInput(img_sub_, face_sub_);
00635       sync_->registerCallback(boost::bind(&FaceRecognitionNodelet::faceImageCallback, this, _1, _2));
00636     }
00637   }
00638 
00639   void unsubscribe()  // NOLINT(modernize-use-override)
00640   {
00641     NODELET_DEBUG("unsubscribe");
00642     img_sub_.unsubscribe();
00643     face_sub_.unsubscribe();
00644   }
00645 
00646 public:
00647   virtual void onInit()  // NOLINT(modernize-use-override)
00648   {
00649     Nodelet::onInit();
00650 
00651     // variables
00652     face_model_size_ = cv::Size(190, 90);
00653 
00654     // dynamic reconfigures
00655     cfg_srv_ = boost::make_shared<Server>(*pnh_);
00656     Server::CallbackType f = boost::bind(&FaceRecognitionNodelet::configCallback, this, _1, _2);
00657     cfg_srv_->setCallback(f);
00658 
00659     // parameters
00660     pnh_->param("approximate_sync", use_async_, false);
00661     pnh_->param("queue_size", queue_size_, 100);
00662 
00663     // advertise
00664     debug_img_pub_ = advertise<sensor_msgs::Image>(*pnh_, "debug_image", 1);
00665     face_pub_ = advertise<opencv_apps::FaceArrayStamped>(*pnh_, "output", 1);
00666     train_srv_ = pnh_->advertiseService("train", &FaceRecognitionNodelet::trainCallback, this);
00667     it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
00668 
00669     onInitPostProcess();
00670   }
00671 };
00672 }  // namespace opencv_apps
00673 
00674 namespace face_recognition
00675 {
00676 class FaceRecognitionNodelet : public opencv_apps::FaceRecognitionNodelet
00677 {
00678 public:
00679   virtual void onInit()  // NOLINT(modernize-use-override)
00680   {
00681     ROS_WARN("DeprecationWarning: Nodelet face_recognition/face_recognition is deprecated, "
00682              "and renamed to opencv_apps/face_recognition.");
00683     opencv_apps::FaceRecognitionNodelet::onInit();
00684   }
00685 };
00686 }  // namespace face_recognition
00687 
00688 #include <pluginlib/class_list_macros.h>
00689 PLUGINLIB_EXPORT_CLASS(opencv_apps::FaceRecognitionNodelet, nodelet::Nodelet);
00690 PLUGINLIB_EXPORT_CLASS(face_recognition::FaceRecognitionNodelet, nodelet::Nodelet);


opencv_apps
Author(s): Kei Okada
autogenerated on Mon Apr 22 2019 02:18:26