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;
77 #if CV_MAJOR_VERSION >= 4
78 #include <opencv2/imgcodecs/legacy/constants_c.h>
79 #include <opencv2/imgproc/imgproc_c.h>
85 #if BOOST_VERSION < 105000
92 #if BOOST_VERSION < 108300
94 path& path::append<typename path::iterator>(
typename path::iterator lhs,
typename path::iterator rhs,
95 const codecvt_type& cvt)
97 for (; lhs != rhs; ++lhs)
104 #if BOOST_VERSION < 108300
105 path::const_iterator it(p.begin());
113 std::string user_dir = (*it).string();
114 if (user_dir.length() == 0 || user_dir[0] !=
'~')
118 if (user_dir.length() == 1)
120 homedir = getenv(
"HOME");
121 if (homedir ==
nullptr)
123 homedir = getpwuid(getuid())->pw_dir;
128 std::string uname = user_dir.substr(1, user_dir.length());
129 passwd* pw = getpwnam(uname.c_str());
132 homedir = pw->pw_dir;
136 ret = path(std::string(homedir));
137 #if BOOST_VERSION < 108300
138 return ret.append(++it, p.end(), path::codecvt());
141 for (; it != p.end(); ++it)
155 std::map<std::string, int>
m_;
158 void add(std::vector<std::string>& l)
161 for (std::map<std::string, int>::const_iterator it = m_.begin(); it != m_.end(); ++it)
166 for (
const std::string& i : l)
168 if (m_.find(i) == m_.end())
175 std::vector<int>
get(std::vector<std::string>& v)
177 std::vector<int> ret(v.size());
178 for (
size_t i = 0; i < v.size(); ++i)
186 for (std::map<std::string, int>::const_iterator it = m_.begin(); it != m_.end(); ++it)
188 if (it->second ==
id)
193 const std::map<std::string, int>&
getMap()
const
201 for (std::map<std::string, int>::const_iterator it = m_.begin(); it != m_.end(); ++it)
217 if (!fs::exists(base_dir_))
221 if (!fs::is_directory(base_dir_))
223 std::stringstream ss;
224 ss << base_dir_ <<
" is not a directory";
225 throw std::runtime_error(ss.str());
230 if (!fs::create_directories(base_dir_))
232 std::stringstream ss;
233 ss <<
"failed to initialize directory: " << base_dir_;
234 throw std::runtime_error(ss.str());
238 void load(std::vector<cv::Mat>& images, std::vector<std::string>& labels,
bool append =
true)
245 fs::directory_iterator end;
246 for (fs::directory_iterator it(base_dir_); it != end; ++it)
248 if (fs::is_directory(*it))
250 std::string label = it->path().stem().string();
251 for (fs::directory_iterator cit(it->path()); cit != end; ++cit)
253 if (fs::is_directory(*cit))
255 fs::path file_path = cit->path();
258 cv::Mat img = cv::imread(file_path.string(), CV_LOAD_IMAGE_COLOR);
259 labels.push_back(label);
260 images.push_back(img);
262 catch (cv::Exception& e)
264 ROS_ERROR_STREAM(
"Error: load image from " << file_path <<
": " << e.what());
271 void save(
const std::vector<cv::Mat>& images,
const std::vector<std::string>& labels)
273 if (images.size() != labels.size())
275 throw std::length_error(
"images.size() != labels.size()");
277 for (
size_t i = 0; i < images.size(); ++i)
279 save(images[i], labels[i]);
283 void save(
const cv::Mat& image,
const std::string& label)
285 fs::path img_dir = base_dir_ / fs::path(label);
286 if (!fs::exists(img_dir) && !fs::create_directories(img_dir))
288 std::stringstream ss;
289 ss <<
"failed to initialize directory: " << img_dir;
290 throw std::runtime_error(ss.str());
292 fs::directory_iterator end;
294 for (fs::directory_iterator it(img_dir); it != end; ++it)
296 if (!fs::is_directory(*it))
300 std::stringstream ss;
302 ss << label <<
"_" << std::setw(6) << std::setfill(
'0') << file_count <<
".jpg";
303 fs::path file_path = img_dir / ss.str();
307 cv::imwrite(file_path.string(), image);
309 catch (cv::Exception& e)
318 typedef opencv_apps::FaceRecognitionConfig
Config;
319 typedef dynamic_reconfigure::Server<Config>
Server;
350 cv::Rect r(
int(
face.face.x -
face.face.width / 2.0 -
face.face.width * face_padding_ / 2.0),
351 int(
face.face.y -
face.face.height / 2.0 -
face.face.height * face_padding_ / 2.0),
352 int(
face.face.width +
face.face.width * face_padding_),
353 int(
face.face.height +
face.face.height * face_padding_));
354 cv::Scalar color(0.0, 0.0, 255.0);
356 cv::rectangle(img, r.tl(), r.br(), color, boldness, CV_AA);
358 double font_scale = 1.5;
359 int text_height = 20;
361 if (r.br().y + text_height > img.rows)
362 text_bl = r.tl() + cv::Point(0, -text_height);
364 text_bl = r.br() + cv::Point(-r.width, text_height);
365 std::stringstream ss;
366 ss <<
face.label <<
" (" << std::fixed << std::setprecision(2) <<
face.confidence <<
")";
367 cv::putText(img, ss.str(), text_bl, cv::FONT_HERSHEY_PLAIN, font_scale, color, boldness, CV_AA);
370 void extractImage(
const cv::Mat& img,
const opencv_apps::Rect& rect, cv::Mat& ret,
double padding = 0.0)
372 int x = std::max(0,
int(rect.x - rect.width / 2.0 - rect.width * padding / 2.0));
373 int y = std::max(0,
int(rect.y - rect.height / 2.0 - rect.height * padding / 2.0));
374 cv::Rect r(x, y, std::min(img.cols - x,
int(rect.width + rect.width * padding)),
375 std::min(img.rows - y,
int(rect.height + rect.height * padding)));
379 void extractImage(
const cv::Mat& img,
const opencv_apps::Face&
face, cv::Mat& ret,
double padding = 0.0)
381 extractImage(img,
face.face, ret, padding);
387 std::vector<cv::Mat> images;
388 std::vector<std::string> labels;
389 train(images, labels);
392 void train(std::vector<cv::Mat>& images, std::vector<std::string>& labels)
394 size_t new_image_size = images.size();
398 storage_->load(images, labels);
404 std::vector<cv::Mat> resized_images(images.size());
405 for (
int i = 0; i < images.size(); ++i)
407 cv::resize(images[i], resized_images[i], face_model_size_, 0, 0, cv::INTER_CUBIC);
408 cv::cvtColor(resized_images[i], resized_images[i], CV_BGR2GRAY);
411 label_mapper_->add(labels);
412 std::vector<int> ids = label_mapper_->get(labels);
415 model_->train(resized_images, ids);
417 if (save_train_data_ && new_image_size > 0)
419 std::vector<cv::Mat> new_images(images.begin(), images.begin() + new_image_size);
420 std::vector<std::string> new_labels(labels.begin(), labels.begin() + new_image_size);
421 storage_->save(new_images, new_labels);
425 void predict(
const cv::Mat& img,
int& label,
double& confidence)
428 cv::resize(img, resized_img, face_model_size_, 0, 0, cv::INTER_CUBIC);
429 cv::cvtColor(resized_img, resized_img, CV_BGR2GRAY);
430 model_->predict(resized_img, label, confidence);
433 void faceImageCallback(
const sensor_msgs::Image::ConstPtr& image,
const opencv_apps::FaceArrayStamped::ConstPtr& faces)
436 boost::mutex::scoped_lock lock(mutex_);
439 if (label_mapper_->getMap().empty())
451 opencv_apps::FaceArrayStamped ret_msg = *faces;
452 for (
size_t i = 0; i < faces->faces.size(); ++i)
454 cv::Mat face_img, resized_image;
455 extractImage(cv_img, faces->faces[i], face_img, face_padding_);
458 double confidence = 0.0;
459 predict(face_img, label_id, confidence);
462 ret_msg.faces[i].label = label_mapper_->lookup(label_id);
463 ret_msg.faces[i].confidence = confidence;
466 if (publish_debug_image)
467 drawFace(cv_img, ret_msg.faces[i]);
470 if (publish_debug_image)
473 debug_img_pub_.
publish(debug_img);
477 catch (cv::Exception& e)
479 NODELET_ERROR_STREAM(
"error at image processing: " << e.err <<
" " << e.func <<
" " << e.file <<
" " << e.line);
483 bool trainCallback(opencv_apps::FaceRecognitionTrain::Request& req, opencv_apps::FaceRecognitionTrain::Response& res)
485 boost::mutex::scoped_lock lock(mutex_);
488 std::vector<cv::Mat> images(req.images.size());
489 bool use_roi = !req.rects.empty();
491 if (use_roi && req.images.size() != req.rects.size())
493 throw std::length_error(
"req.images.size() != req.rects.size()");
496 for (
size_t i = 0; i < req.images.size(); ++i)
498 sensor_msgs::Image img = req.images[i];
503 extractImage(images[i], req.rects[i], face_img);
504 images[i] = face_img;
507 std::vector<std::string> labels(req.labels.begin(), req.labels.end());
508 train(images, labels);
512 catch (cv::Exception& e)
514 std::stringstream ss;
515 ss <<
"error at training: " << e.err <<
" " << e.func <<
" " << e.file <<
" " << e.line;
517 res.error = ss.str();
524 boost::mutex::scoped_lock lock(mutex_);
526 bool need_recreate_model =
false;
527 bool need_retrain =
false;
529 use_saved_data_ = config.use_saved_data;
530 save_train_data_ = config.save_train_data;
531 face_padding_ = config.face_padding;
533 if (face_model_size_.width != config.face_model_width)
535 face_model_size_.width = config.face_model_width;
538 if (face_model_size_.height != config.face_model_height)
540 face_model_size_.height = config.face_model_height;
544 if (data_dir_ != config.data_dir)
546 data_dir_ = config.data_dir;
549 storage_.reset(
new Storage(fs::path(data_dir_)));
552 if (config_.model_method != config.model_method)
554 need_recreate_model =
true;
557 if (config_.model_num_components != config.model_num_components)
559 need_recreate_model =
true;
562 if (config.model_method ==
"LBPH" &&
563 (config_.lbph_radius != config.lbph_radius || config_.lbph_neighbors != config.lbph_neighbors ||
564 config_.lbph_grid_x != config.lbph_grid_x || config_.lbph_grid_y != config.lbph_grid_y))
566 need_recreate_model =
true;
569 if (need_recreate_model)
573 if (config.model_method ==
"eigen")
576 #if (CV_MAJOR_VERSION >= 4) || (CV_MAJOR_VERSION >= 3 && CV_MINOR_VERSION >= 3)
577 model_ = face::EigenFaceRecognizer::create(config.model_num_components, config.model_threshold);
579 model_ = face::createEigenFaceRecognizer(config.model_num_components, config.model_threshold);
582 else if (config.model_method ==
"fisher")
584 #if (CV_MAJOR_VERSION >= 4) || (CV_MAJOR_VERSION >= 3 && CV_MINOR_VERSION >= 3)
585 model_ = face::FisherFaceRecognizer::create(config.model_num_components, config.model_threshold);
587 model_ = face::createFisherFaceRecognizer(config.model_num_components, config.model_threshold);
590 else if (config.model_method ==
"LBPH")
592 #if (CV_MAJOR_VERSION >= 4) || (CV_MAJOR_VERSION >= 3 && CV_MINOR_VERSION >= 3)
593 model_ = face::LBPHFaceRecognizer::create(config.lbph_radius, config.lbph_neighbors, config.lbph_grid_x,
596 model_ = face::createLBPHFaceRecognizer(config.lbph_radius, config.lbph_neighbors, config.lbph_grid_x,
602 catch (cv::Exception& e)
614 catch (cv::Exception& e)
620 if (config_.model_threshold != config.model_threshold)
624 #if CV_MAJOR_VERSION >= 3
625 if (face::BasicFaceRecognizer* model =
dynamic_cast<face::BasicFaceRecognizer*
>(model_.get()))
627 model->setThreshold(config.model_threshold);
629 else if (face::LBPHFaceRecognizer* model =
dynamic_cast<face::LBPHFaceRecognizer*
>(model_.get()))
631 model->setThreshold(config.model_threshold);
634 model_->set(
"threshold", config.model_threshold);
637 catch (cv::Exception& e)
652 async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> >(queue_size_);
653 async_->connectInput(img_sub_, face_sub_);
654 async_->registerCallback(boost::bind(&FaceRecognitionNodelet::faceImageCallback,
this,
boost::placeholders::_1,
659 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(queue_size_);
660 sync_->connectInput(img_sub_, face_sub_);
685 face_model_size_ = cv::Size(190, 90);
688 cfg_srv_ = boost::make_shared<Server>(*pnh_);
689 Server::CallbackType
f =
691 cfg_srv_->setCallback(
f);
694 pnh_->param(
"approximate_sync", use_async_,
false);
695 pnh_->param(
"queue_size", queue_size_, 100);
698 debug_img_pub_ = advertise<sensor_msgs::Image>(*pnh_,
"debug_image", 1);
699 face_pub_ = advertise<opencv_apps::FaceArrayStamped>(*pnh_,
"output", 1);
700 train_srv_ = pnh_->advertiseService(
"train", &FaceRecognitionNodelet::trainCallback,
this);
715 ROS_WARN(
"DeprecationWarning: Nodelet face_recognition/face_recognition is deprecated, "
716 "and renamed to opencv_apps/face_recognition.");
722 #ifdef USE_PLUGINLIB_CLASS_LIST_MACROS_H