36 #include <boost/filesystem.hpp> 37 #include <boost/shared_ptr.hpp> 38 #include <boost/thread.hpp> 39 #include <boost/version.hpp> 44 #include <opencv2/opencv.hpp> 49 #include <dynamic_reconfigure/server.h> 59 #include <opencv_apps/FaceArrayStamped.h> 60 #include <opencv_apps/FaceRecognitionTrain.h> 61 #include <opencv_apps/FaceRecognitionConfig.h> 64 #if BOOST_VERSION < 105000 67 namespace fs = boost::filesystem;
70 #if CV_MAJOR_VERSION >= 3 71 #include <opencv2/face.hpp> 72 namespace face = cv::face;
80 #if BOOST_VERSION < 105000 88 path& path::append<typename path::iterator>(
typename path::iterator lhs,
typename path::iterator rhs,
89 const codecvt_type& cvt)
91 for (; lhs != rhs; ++lhs)
97 path::const_iterator it(p.begin());
98 std::string user_dir = (*it).string();
99 if (user_dir.length() == 0 || user_dir[0] !=
'~')
103 if (user_dir.length() == 1)
105 homedir = getenv(
"HOME");
106 if (homedir ==
nullptr)
108 homedir = getpwuid(getuid())->pw_dir;
113 std::string uname = user_dir.substr(1, user_dir.length());
114 passwd* pw = getpwnam(uname.c_str());
117 homedir = pw->pw_dir;
119 ret = path(std::string(homedir));
120 return ret.append(++it, p.end(), path::codecvt());
129 std::map<std::string, int>
m_;
132 void add(std::vector<std::string>& l)
135 for (std::map<std::string, int>::const_iterator it = m_.begin(); it != m_.end(); ++it)
140 for (
const std::string& i : l)
142 if (m_.find(i) == m_.end())
149 std::vector<int>
get(std::vector<std::string>& v)
151 std::vector<int> ret(v.size());
152 for (
size_t i = 0; i < v.size(); ++i)
160 for (std::map<std::string, int>::const_iterator it = m_.begin(); it != m_.end(); ++it)
162 if (it->second ==
id)
167 const std::map<std::string, int>&
getMap()
const 175 for (std::map<std::string, int>::const_iterator it = m_.begin(); it != m_.end(); ++it)
191 if (!fs::exists(base_dir_))
195 if (!fs::is_directory(base_dir_))
197 std::stringstream ss;
198 ss << base_dir_ <<
" is not a directory";
199 throw std::runtime_error(ss.str());
204 if (!fs::create_directories(base_dir_))
206 std::stringstream ss;
207 ss <<
"failed to initialize directory: " << base_dir_;
208 throw std::runtime_error(ss.str());
212 void load(std::vector<cv::Mat>& images, std::vector<std::string>& labels,
bool append =
true)
219 fs::directory_iterator end;
220 for (fs::directory_iterator it(base_dir_); it != end; ++it)
222 if (fs::is_directory(*it))
224 std::string label = it->path().stem().string();
225 for (fs::directory_iterator cit(it->path()); cit != end; ++cit)
227 if (fs::is_directory(*cit))
229 fs::path file_path = cit->path();
232 cv::Mat img = cv::imread(file_path.string(), CV_LOAD_IMAGE_COLOR);
233 labels.push_back(label);
234 images.push_back(img);
236 catch (cv::Exception& e)
238 ROS_ERROR_STREAM(
"Error: load image from " << file_path <<
": " << e.what());
245 void save(
const std::vector<cv::Mat>& images,
const std::vector<std::string>& labels)
247 if (images.size() != labels.size())
249 throw std::length_error(
"images.size() != labels.size()");
251 for (
size_t i = 0; i < images.size(); ++i)
253 save(images[i], labels[i]);
257 void save(
const cv::Mat& image,
const std::string& label)
259 fs::path img_dir = base_dir_ / fs::path(label);
260 if (!fs::exists(img_dir) && !fs::create_directories(img_dir))
262 std::stringstream ss;
263 ss <<
"failed to initialize directory: " << img_dir;
264 throw std::runtime_error(ss.str());
266 fs::directory_iterator end;
268 for (fs::directory_iterator it(img_dir); it != end; ++it)
270 if (!fs::is_directory(*it))
274 std::stringstream ss;
276 ss << label <<
"_" << std::setw(6) << std::setfill(
'0') << file_count <<
".jpg";
277 fs::path file_path = img_dir / ss.str();
281 cv::imwrite(file_path.string(), image);
283 catch (cv::Exception& e)
292 typedef opencv_apps::FaceRecognitionConfig
Config;
293 typedef dynamic_reconfigure::Server<Config>
Server;
322 void drawFace(cv::Mat& img,
const opencv_apps::Face& face)
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);
330 cv::rectangle(img, r.tl(), r.br(), color, boldness, CV_AA);
332 double font_scale = 1.5;
333 int text_height = 20;
335 if (r.br().y + text_height > img.rows)
336 text_bl = r.tl() + cv::Point(0, -text_height);
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);
344 void extractImage(
const cv::Mat& img,
const opencv_apps::Rect& rect, cv::Mat& ret,
double padding = 0.0)
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)));
353 void extractImage(
const cv::Mat& img,
const opencv_apps::Face& face, cv::Mat& ret,
double padding = 0.0)
355 extractImage(img, face.face, ret, padding);
361 std::vector<cv::Mat> images;
362 std::vector<std::string> labels;
363 train(images, labels);
366 void train(std::vector<cv::Mat>& images, std::vector<std::string>& labels)
368 size_t new_image_size = images.size();
372 storage_->load(images, labels);
378 std::vector<cv::Mat> resized_images(images.size());
379 for (
int i = 0; i < images.size(); ++i)
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);
385 label_mapper_->add(labels);
386 std::vector<int> ids = label_mapper_->get(labels);
389 model_->train(resized_images, ids);
391 if (save_train_data_ && new_image_size > 0)
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);
399 void predict(
const cv::Mat& img,
int& label,
double& confidence)
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);
408 const opencv_apps::FaceArrayStamped::ConstPtr& faces)
411 boost::mutex::scoped_lock lock(mutex_);
414 if (label_mapper_->getMap().empty())
426 opencv_apps::FaceArrayStamped ret_msg = *faces;
427 for (
size_t i = 0; i < faces->faces.size(); ++i)
429 cv::Mat face_img, resized_image;
430 extractImage(cv_img, faces->faces[i], face_img, face_padding_);
433 double confidence = 0.0;
434 predict(face_img, label_id, confidence);
437 ret_msg.faces[i].label = label_mapper_->lookup(label_id);
438 ret_msg.faces[i].confidence = confidence;
441 if (publish_debug_image)
442 drawFace(cv_img, ret_msg.faces[i]);
445 if (publish_debug_image)
448 debug_img_pub_.
publish(debug_img);
452 catch (cv::Exception& e)
454 NODELET_ERROR_STREAM(
"error at image processing: " << e.err <<
" " << e.func <<
" " << e.file <<
" " << e.line);
458 bool trainCallback(opencv_apps::FaceRecognitionTrain::Request& req, opencv_apps::FaceRecognitionTrain::Response& res)
460 boost::mutex::scoped_lock lock(mutex_);
463 std::vector<cv::Mat> images(req.images.size());
464 bool use_roi = !req.rects.empty();
466 if (use_roi && req.images.size() != req.rects.size())
468 throw std::length_error(
"req.images.size() != req.rects.size()");
471 for (
size_t i = 0; i < req.images.size(); ++i)
473 sensor_msgs::Image img = req.images[i];
478 extractImage(images[i], req.rects[i], face_img);
479 images[i] = face_img;
482 std::vector<std::string> labels(req.labels.begin(), req.labels.end());
483 train(images, labels);
487 catch (cv::Exception& e)
489 std::stringstream ss;
490 ss <<
"error at training: " << e.err <<
" " << e.func <<
" " << e.file <<
" " << e.line;
492 res.error = ss.str();
499 boost::mutex::scoped_lock lock(mutex_);
501 bool need_recreate_model =
false;
502 bool need_retrain =
false;
504 use_saved_data_ = config.use_saved_data;
505 save_train_data_ = config.save_train_data;
506 face_padding_ = config.face_padding;
508 if (face_model_size_.width != config.face_model_width)
510 face_model_size_.width = config.face_model_width;
513 if (face_model_size_.height != config.face_model_height)
515 face_model_size_.height = config.face_model_height;
519 if (data_dir_ != config.data_dir)
521 data_dir_ = config.data_dir;
524 storage_.reset(
new Storage(fs::path(data_dir_)));
527 if (config_.model_method != config.model_method)
529 need_recreate_model =
true;
532 if (config_.model_num_components != config.model_num_components)
534 need_recreate_model =
true;
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))
541 need_recreate_model =
true;
544 if (need_recreate_model)
548 if (config.model_method ==
"eigen")
551 #if CV_MAJOR_VERSION >= 3 && CV_MINOR_VERSION >= 3 552 model_ = face::EigenFaceRecognizer::create(config.model_num_components, config.model_threshold);
554 model_ = face::createEigenFaceRecognizer(config.model_num_components, config.model_threshold);
557 else if (config.model_method ==
"fisher")
559 #if CV_MAJOR_VERSION >= 3 && CV_MINOR_VERSION >= 3 560 model_ = face::FisherFaceRecognizer::create(config.model_num_components, config.model_threshold);
562 model_ = face::createFisherFaceRecognizer(config.model_num_components, config.model_threshold);
565 else if (config.model_method ==
"LBPH")
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,
571 model_ = face::createLBPHFaceRecognizer(config.lbph_radius, config.lbph_neighbors, config.lbph_grid_x,
577 catch (cv::Exception& e)
589 catch (cv::Exception& e)
595 if (config_.model_threshold != config.model_threshold)
599 #if CV_MAJOR_VERSION >= 3 600 if (face::BasicFaceRecognizer* model = dynamic_cast<face::BasicFaceRecognizer*>(model_.get()))
602 model->setThreshold(config.model_threshold);
604 else if (face::LBPHFaceRecognizer* model = dynamic_cast<face::LBPHFaceRecognizer*>(model_.get()))
606 model->setThreshold(config.model_threshold);
609 model_->set(
"threshold", config.model_threshold);
612 catch (cv::Exception& e)
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));
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));
652 face_model_size_ = cv::Size(190, 90);
655 cfg_srv_ = boost::make_shared<Server>(*pnh_);
656 Server::CallbackType
f = boost::bind(&FaceRecognitionNodelet::configCallback,
this, _1, _2);
657 cfg_srv_->setCallback(f);
660 pnh_->param(
"approximate_sync", use_async_,
false);
661 pnh_->param(
"queue_size", queue_size_, 100);
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);
681 ROS_WARN(
"DeprecationWarning: Nodelet face_recognition/face_recognition is deprecated, " 682 "and renamed to opencv_apps/face_recognition.");
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
boost::shared_ptr< Server > cfg_srv_
Nodelet to automatically subscribe/unsubscribe topics according to subscription of advertised topics...
boost::shared_ptr< LabelMapper > label_mapper_
Demo code to calculate moments.
std::string lookup(int id)
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)
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(...)
ros::Publisher debug_img_pub_
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)
boost::shared_ptr< Storage > storage_
#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)
cv::Size face_model_size_
#define ROS_ERROR_STREAM(args)
boost::shared_ptr< image_transport::ImageTransport > it_
dynamic_reconfigure::Server< Config > Server
ros::ServiceServer train_srv_
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)