From 3570b8094e093e6e8f64af7e630b2d69b716da32 Mon Sep 17 00:00:00 2001 From: Yuki Furuta Date: Sun, 30 Apr 2017 22:07:54 +0900 Subject: [PATCH 1/3] [CMakeLists.txt] remove duplicate msg: RectArrayStamped.msg --- CMakeLists.txt | 1 - 1 file changed, 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index b4d309c0..3b38c90a 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -63,7 +63,6 @@ add_message_files( FlowStamped.msg FlowArray.msg FlowArrayStamped.msg - RectArrayStamped.msg Size.msg Face.msg FaceArray.msg From cc1e47a82085151941ac30efe0d76414bd1dda67 Mon Sep 17 00:00:00 2001 From: Yuki Furuta Date: Sun, 30 Apr 2017 22:08:43 +0900 Subject: [PATCH 2/3] [Face.msg] add label / confidence for face recognition --- msg/Face.msg | 2 ++ 1 file changed, 2 insertions(+) diff --git a/msg/Face.msg b/msg/Face.msg index 557556b6..789e0cfe 100644 --- a/msg/Face.msg +++ b/msg/Face.msg @@ -1,2 +1,4 @@ Rect face Rect[] eyes +string label +float64 confidence From 64964db9c3e8d1fde67830db9aa5117924d7208e Mon Sep 17 00:00:00 2001 From: Yuki Furuta Date: Sun, 30 Apr 2017 22:13:37 +0900 Subject: [PATCH 3/3] add face_recognition nodelet / test --- CMakeLists.txt | 12 +- cfg/FaceRecognition.cfg | 61 +++ launch/face_recognition.launch | 41 ++ nodelet_plugins.xml | 4 + scripts/face_recognition_trainer.py | 97 ++++ src/nodelet/face_recognition_nodelet.cpp | 559 +++++++++++++++++++++++ srv/FaceRecognitionTrain.srv | 6 + test/CMakeLists.txt | 12 + test/face_data.tar.gz | Bin 0 -> 10556 bytes test/test-face_recognition.test | 32 ++ 10 files changed, 822 insertions(+), 2 deletions(-) create mode 100755 cfg/FaceRecognition.cfg create mode 100644 launch/face_recognition.launch create mode 100755 scripts/face_recognition_trainer.py create mode 100644 src/nodelet/face_recognition_nodelet.cpp create mode 100644 srv/FaceRecognitionTrain.srv create mode 100644 test/face_data.tar.gz create mode 100644 test/test-face_recognition.test diff --git a/CMakeLists.txt b/CMakeLists.txt index 3b38c90a..fb39261f 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,7 +1,7 @@ cmake_minimum_required(VERSION 2.8.3) project(opencv_apps) -find_package(catkin REQUIRED COMPONENTS cv_bridge dynamic_reconfigure message_generation image_transport nodelet roscpp) +find_package(catkin REQUIRED COMPONENTS cv_bridge dynamic_reconfigure message_generation image_transport nodelet roscpp sensor_msgs) find_package(OpenCV REQUIRED) message(STATUS "OpenCV VERSION: ${OpenCV_VERSION}") @@ -32,6 +32,7 @@ generate_dynamic_reconfigure_options( cfg/EdgeDetection.cfg cfg/HoughLines.cfg cfg/HoughCircles.cfg cfg/FindContours.cfg cfg/ConvexHull.cfg cfg/GeneralContours.cfg cfg/ContourMoments.cfg cfg/FaceDetection.cfg + cfg/FaceRecognition.cfg cfg/GoodfeatureTrack.cfg cfg/CornerHarris.cfg # @@ -85,9 +86,15 @@ add_message_files( ContourArrayStamped.msg ) +add_service_files( + FILES + FaceRecognitionTrain.srv +) + ## Generate added messages and services with any dependencies listed here generate_messages( DEPENDENCIES + sensor_msgs std_msgs ) @@ -252,6 +259,7 @@ opencv_apps_add_nodelet(camshift camshift/camshift src/nodelet/camshift_nodelet. # ./em.cpp # ./example_cmake/example.cpp opencv_apps_add_nodelet(face_detection face_detection/face_detection src/nodelet/face_detection_nodelet.cpp) # ./facedetect.cpp +opencv_apps_add_nodelet(face_recognition face_recognition/face_recognition src/nodelet/face_recognition_nodelet.cpp) # ./facial_features.cpp opencv_apps_add_nodelet(fback_flow fback_flow/fback_flow src/nodelet/fback_flow_nodelet.cpp) # ./fback.cpp # ./ffilldemo.cpp @@ -342,7 +350,7 @@ install(TARGETS ${_opencv_apps_nodelet_targets} install(FILES nodelet_plugins.xml DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} ) -install(DIRECTORY launch test +install(DIRECTORY launch test scripts DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} USE_SOURCE_PERMISSIONS) diff --git a/cfg/FaceRecognition.cfg b/cfg/FaceRecognition.cfg new file mode 100755 index 00000000..bdff7139 --- /dev/null +++ b/cfg/FaceRecognition.cfg @@ -0,0 +1,61 @@ +#! /usr/bin/env python +# Software License Agreement (BSD License) +# +# Copyright (c) 2017, Yuki Furuta. +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of Kei Okada nor the names of its +# contributors may be used to endorse or promote products derived +# from this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + + +PACKAGE='face_recognition' + +from dynamic_reconfigure.parameter_generator_catkin import * + +gen = ParameterGenerator() + +methods = gen.enum([gen.const("eigen", str_t, "eigen", "eigen"), + gen.const("fisher", str_t, "fisher", "fisher"), + gen.const("LBPH", str_t, "LBPH", "LBPH")], + "Method to recognize faces") + +# variable type level description default min max +gen.add("model_method", str_t, 0, "Method to recognize faces", "eigen", edit_method=methods) +gen.add("use_saved_data", bool_t, 0, "Use saved data", True) +gen.add("save_train_data", bool_t, 0, "Save train data", True) +gen.add("data_dir", str_t, 0, "Save directory for train data", "~/.ros/opencv_apps/face_data") +gen.add("face_model_width", int_t, 0, "Width of training face image", 190, 30, 500) +gen.add("face_model_height", int_t, 0, "Height of training face image", 90, 30, 500) +gen.add("face_padding", double_t, 0, "Padding ratio of each face", 0.1, 0.0, 2.0) +gen.add("model_num_components", int_t, 0, "Number of components for face recognizer model", 0, 0, 100) +gen.add("model_threshold", double_t, 0, "Threshold for face recognizer model", 8000.0, 0.0, 10000.0) +gen.add("lbph_radius", int_t, 0, "Radius parameter used only for LBPH model", 1, 1, 10) +gen.add("lbph_neighbors", int_t, 0, "Neighbors parameter used only for LBPH model", 8, 1, 30) +gen.add("lbph_grid_x", int_t, 0, "grid_x parameter used only for LBPH model", 8, 1, 30) +gen.add("lbph_grid_y", int_t, 0, "grid_y parameter used only for LBPH model", 8, 1, 30) + +exit(gen.generate(PACKAGE, "face_recognition", "FaceRecognition")) diff --git a/launch/face_recognition.launch b/launch/face_recognition.launch new file mode 100644 index 00000000..b7dbca80 --- /dev/null +++ b/launch/face_recognition.launch @@ -0,0 +1,41 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/nodelet_plugins.xml b/nodelet_plugins.xml index 74a7466b..1ab76dac 100644 --- a/nodelet_plugins.xml +++ b/nodelet_plugins.xml @@ -43,6 +43,10 @@ Nodelet to find faces + + Nodelet to identify faces + + Nodelet for detecting corners using Shi-Tomasi method diff --git a/scripts/face_recognition_trainer.py b/scripts/face_recognition_trainer.py new file mode 100755 index 00000000..b62c5e30 --- /dev/null +++ b/scripts/face_recognition_trainer.py @@ -0,0 +1,97 @@ +#! /usr/bin/env python +# Software License Agreement (BSD License) +# +# Copyright (c) 2017, Yuki Furuta. +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of Kei Okada nor the names of its +# contributors may be used to endorse or promote products derived +# from this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + + +from __future__ import print_function + +try: + input = raw_input +except: + pass + +import rospy +import message_filters +from sensor_msgs.msg import Image +from opencv_apps.msg import FaceArrayStamped +from opencv_apps.srv import FaceRecognitionTrain, FaceRecognitionTrainRequest + +class FaceRecognitionTrainer(object): + def __init__(self): + self.queue_size = rospy.get_param("~queue_size", 100) + + self.img_sub = message_filters.Subscriber("image", Image) + self.face_sub = message_filters.Subscriber("faces", FaceArrayStamped) + + self.req = FaceRecognitionTrainRequest() + self.label = "" + self.ok = False + + self.sync = message_filters.TimeSynchronizer([self.img_sub, self.face_sub], + self.queue_size) + self.sync.registerCallback(self.callback) + def callback(self, img, faces): + if len(faces.faces) <= 0: + return + if self.ok: + faces.faces.sort(key=lambda f: f.face.width * f.face.height) + self.req.images.append(img) + self.req.rects.append(faces.faces[0].face) + self.req.labels.append(self.label) + self.ok = False + def run(self): + rospy.wait_for_service("train") + train = rospy.ServiceProxy("train", FaceRecognitionTrain) + self.label = input("Please input your name and press Enter: ") + while len(self.label) <= 0 or input("Your name is %s. Correct? [y/n]: " % self.label) not in ["", "y", "Y"]: + self.label = input("Please input your name and press Enter: ") + + input("Please stand at the center of the camera and press Enter: ") + while True: + self.ok = True + while self.ok: + print("taking picture...") + rospy.sleep(1) + if input("One more picture? [y/n]: ") not in ["", "y", "Y"]: + break + print("sending to trainer...") + + res = train(self.req) + if res.ok: + print("OK. Trained successfully!") + else: + print("NG. Error: %s" % res.error) + +if __name__ == '__main__': + rospy.init_node("face_recognition_trainer") + t = FaceRecognitionTrainer() + t.run() diff --git a/src/nodelet/face_recognition_nodelet.cpp b/src/nodelet/face_recognition_nodelet.cpp new file mode 100644 index 00000000..24b8051e --- /dev/null +++ b/src/nodelet/face_recognition_nodelet.cpp @@ -0,0 +1,559 @@ +/********************************************************************* +* Software License Agreement (BSD License) +* +* Copyright (c) 2017, Yuki Furuta. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Kei Okada nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +*********************************************************************/ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + + +namespace enc = sensor_msgs::image_encodings; +#if BOOST_VERSION < 105000 +namespace fs = boost::filesystem3; // for hydro +#else +namespace fs = boost::filesystem; +#endif + +#if CV_MAJOR_VERSION >= 3 +#include +namespace face = cv::face; +#else +namespace face = cv; +#endif + +// utility for resolving path +namespace boost { +#if BOOST_VERSION < 105000 +namespace filesystem3 { // for hydro +#else +namespace filesystem { +#endif + template< > + path& path::append( + typename path::iterator lhs, typename path::iterator rhs, const codecvt_type& cvt) { + for(;lhs != rhs; ++lhs) *this /= *lhs; + return *this; + } + path user_expanded_path(const path &p) { + path::const_iterator it(p.begin()); + std::string user_dir = (*it).string(); + if (user_dir.length() == 0 || user_dir[0] != '~') + return p; + path ret; + char* homedir; + if (user_dir.length() == 1) { + homedir = getenv("HOME"); + if (homedir == NULL) { + homedir = getpwuid(getuid())->pw_dir; + } + } else { + std::string uname = user_dir.substr(1, user_dir.length()); + passwd* pw = getpwnam(uname.c_str()); + if (pw == NULL) return p; + homedir = pw->pw_dir; + } + ret = path(std::string(homedir)); + return ret.append(++it, p.end(), path::codecvt()); + } +}} // end of utility for resolving paths + +namespace face_recognition { + + class LabelMapper { + std::map m_; + public: + void add(std::vector &l) { + int id = 0; + for (std::map::const_iterator it = m_.begin(); it != m_.end(); ++it) { + if (id < it->second) id = it->second + 1; + } + for (size_t i = 0; i < l.size(); ++i) { + if (m_.find(l[i]) == m_.end()) { + m_[l[i]] = id; + id++; + } + } + } + std::vector get(std::vector &v) { + std::vector ret(v.size()); + for (size_t i = 0; i < v.size(); ++i) { + ret[i] = m_[v[i]]; + } + return ret; + } + std::string lookup(int id) { + for (std::map::const_iterator it = m_.begin(); it != m_.end(); ++it) { + if (it->second == id) return it->first; + } + return "nan"; + } + + void debugPrint() { + ROS_WARN_STREAM("label mapper: debug print:"); + for (std::map::const_iterator it = m_.begin(); it != m_.end(); ++it) { + ROS_WARN_STREAM("\t" << it->first << ": " << it->second); + } + ROS_WARN_STREAM("label mapper: debug print end"); + } + }; + + class Storage { + fs::path base_dir_; + public: + Storage(const fs::path &base_dir) { + base_dir_ = fs::user_expanded_path(base_dir); + if (!fs::exists(base_dir_)) { + init(); + } + if (!fs::is_directory(base_dir_)) { + std::stringstream ss; + ss << base_dir_ << " is not a directory"; + throw std::runtime_error(ss.str()); + } + }; + void init() { + if (!fs::create_directories(base_dir_)) { + std::stringstream ss; + ss << "failed to initialize directory: " << base_dir_; + throw std::runtime_error(ss.str()); + } + } + + void load(std::vector &images, std::vector &labels, bool append = true) { + if (!append) { + images.clear(); + labels.clear(); + } + fs::directory_iterator end; + for (fs::directory_iterator it(base_dir_); it != end; ++it) { + if (fs::is_directory(*it)) { + std::string label = it->path().stem().string(); + for (fs::directory_iterator cit(it->path()); cit != end; ++cit) { + if (fs::is_directory(*cit)) continue; + fs::path file_path = cit->path(); + try { + cv::Mat img = cv::imread(file_path.string(), CV_LOAD_IMAGE_COLOR); + labels.push_back(label); + images.push_back(img); + } catch (cv::Exception &e) { + ROS_ERROR_STREAM("Error: load image from " << file_path << ": " << e.what()); + } + } + } + } + } + + void save(const std::vector &images, const std::vector &labels) { + if (images.size() != labels.size()) { + throw std::length_error("images.size() != labels.size()"); + } + for (size_t i = 0; i < images.size(); ++i) { + save(images[i], labels[i]); + } + } + + void save(const cv::Mat &image, const std::string &label) { + fs::path img_dir = base_dir_ / fs::path(label); + if (!fs::exists(img_dir) && !fs::create_directories(img_dir)) { + std::stringstream ss; + ss << "failed to initialize directory: " << img_dir; + throw std::runtime_error(ss.str()); + } + fs::directory_iterator end; + int file_count = 0; + for (fs::directory_iterator it(img_dir); it != end; ++it) { + if (!fs::is_directory(*it)) file_count++; + } + + std::stringstream ss; + // data_dir/person_label/person_label_123456.jpg + ss << label << "_" << std::setw(6) << std::setfill('0') << file_count << ".jpg"; + fs::path file_path = img_dir / ss.str(); + ROS_INFO_STREAM("saving image to :" << file_path); + try { + cv::imwrite(file_path.string(), image); + } catch(cv::Exception &e) { + ROS_ERROR_STREAM("Error: save image to " << file_path << ": " << e.what()); + } + } + }; + + class FaceRecognitionNodelet: public opencv_apps::Nodelet + { + typedef face_recognition::FaceRecognitionConfig Config; + typedef dynamic_reconfigure::Server Server; + typedef message_filters::sync_policies::ExactTime< + sensor_msgs::Image, opencv_apps::FaceArrayStamped> SyncPolicy; + typedef message_filters::sync_policies::ApproximateTime< + sensor_msgs::Image, opencv_apps::FaceArrayStamped> ApproximateSyncPolicy; + + Config config_; + boost::shared_ptr cfg_srv_; + boost::shared_ptr it_; + boost::shared_ptr > sync_; + boost::shared_ptr > async_; + image_transport::SubscriberFilter img_sub_; + message_filters::Subscriber face_sub_; + ros::Publisher debug_img_pub_; + ros::Publisher face_pub_; + ros::ServiceServer train_srv_; + + bool save_train_data_; + bool use_async_; + bool use_saved_data_; + double face_padding_; + int queue_size_; + std::string data_dir_; + boost::mutex mutex_; + + boost::shared_ptr label_mapper_; + boost::shared_ptr storage_; + cv::Size face_model_size_; + cv::Ptr model_; + + void drawFace(cv::Mat &img, const opencv_apps::Face &face) { + cv::Rect r(int(face.face.x - face.face.width / 2.0 - face.face.width * face_padding_ / 2.0), + int(face.face.y - face.face.height / 2.0 - face.face.height * face_padding_ / 2.0), + int(face.face.width + face.face.width * face_padding_), + int(face.face.height + face.face.height * face_padding_)); + cv::Scalar color(0.0, 0.0, 255.0); + int boldness = 2; + cv::rectangle(img, r.tl(), r.br(), color, boldness, CV_AA); + + double font_scale = 1.5; + int text_height = 20; + cv::Point text_bl; + if (r.br().y + text_height > img.rows) text_bl = r.tl() + cv::Point(0, -text_height); + else text_bl = r.br() + cv::Point(-r.width, text_height); + std::stringstream ss; + ss << face.label << " (" << std::fixed << std::setprecision(2) << face.confidence << ")"; + cv::putText(img, ss.str(), text_bl, cv::FONT_HERSHEY_PLAIN, font_scale, color, boldness, CV_AA); + } + + void extractImage(const cv::Mat &img, const opencv_apps::Rect &rect, cv::Mat &ret, double padding = 0.0) { + int x = std::max(0, int(rect.x - rect.width / 2.0 - rect.width * padding / 2.0)); + int y = std::max(0, int(rect.y - rect.height / 2.0 - rect.height * padding / 2.0)); + cv::Rect r(x, y, + std::min(img.cols - x, int(rect.width + rect.width * padding)), + std::min(img.rows - y, int(rect.height + rect.height * padding))); + ret = img(r); + } + + void extractImage(const cv::Mat &img, const opencv_apps::Face &face, cv::Mat &ret, double padding = 0.0) { + extractImage(img, face.face, ret, padding); + } + + void retrain() { + NODELET_DEBUG("retrain"); + std::vector images; + std::vector labels; + train(images, labels); + } + + void train(std::vector &images, std::vector &labels) { + size_t new_image_size = images.size(); + + if (use_saved_data_) { + storage_->load(images, labels); + } + + if (images.size() == 0) return; + + std::vector resized_images(images.size()); + for (int i = 0; i < images.size(); ++i) { + cv::resize(images[i], resized_images[i], face_model_size_, + 0, 0, cv::INTER_CUBIC); + cv::cvtColor(resized_images[i], resized_images[i], CV_BGR2GRAY); + } + + label_mapper_->add(labels); + std::vector ids = label_mapper_->get(labels); + NODELET_INFO_STREAM("training with " << images.size() << " images"); + // label_mapper_->debugPrint(); + model_->train(resized_images, ids); + + if (save_train_data_ && new_image_size > 0) { + std::vector new_images(images.begin(), images.begin()+new_image_size); + std::vector new_labels(labels.begin(), labels.begin()+new_image_size); + storage_->save(new_images, new_labels); + } + } + + void predict(const cv::Mat &img, int &label, double &confidence) { + cv::Mat resized_img; + cv::resize(img, resized_img, face_model_size_, 0, 0, cv::INTER_CUBIC); + cv::cvtColor(resized_img, resized_img, CV_BGR2GRAY); + model_->predict(resized_img, label, confidence); + } + + void faceImageCallback(const sensor_msgs::Image::ConstPtr &image, + const opencv_apps::FaceArrayStamped::ConstPtr &faces) { + NODELET_DEBUG("faceImageCallback"); + boost::mutex::scoped_lock lock(mutex_); + + // check if need to draw and publish debug image + bool publish_debug_image = debug_img_pub_.getNumSubscribers() > 0; + + try { + cv::Mat cv_img = cv_bridge::toCvShare(image, enc::BGR8)->image; + opencv_apps::FaceArrayStamped ret_msg = *faces; + for (size_t i = 0; i < faces->faces.size(); ++i) { + cv::Mat face_img, resized_image; + extractImage(cv_img, faces->faces[i], face_img, face_padding_); + + int label_id = -1; + double confidence = 0.0; + predict(face_img, label_id, confidence); + if (label_id == -1) continue; + ret_msg.faces[i].label = label_mapper_->lookup(label_id); + ret_msg.faces[i].confidence = confidence; + + // draw debug image + if (publish_debug_image) drawFace(cv_img, ret_msg.faces[i]); + } + face_pub_.publish(ret_msg); + if (publish_debug_image) { + sensor_msgs::Image::Ptr debug_img + = cv_bridge::CvImage(image->header, enc::BGR8, cv_img).toImageMsg(); + debug_img_pub_.publish(debug_img); + NODELET_DEBUG("Published debug image"); + } + } catch (cv::Exception &e) { + NODELET_ERROR_STREAM("error at image processing: " + << e.err << " " + << e.func << " " + << e.file << " " + << e.line); + } + } + + bool trainCallback(opencv_apps::FaceRecognitionTrain::Request &req, + opencv_apps::FaceRecognitionTrain::Response &res) { + boost::mutex::scoped_lock lock(mutex_); + try { + std::vector images(req.images.size()); + bool use_roi = req.rects.size() == 0 ? false : true; + + if (use_roi && req.images.size() != req.rects.size()) { + throw std::length_error("req.images.size() != req.rects.size()"); + } + + for (size_t i = 0; i < req.images.size(); ++i) { + sensor_msgs::Image img = req.images[i]; + images[i] = cv_bridge::toCvCopy(img, enc::BGR8)->image; + if (use_roi) { + cv::Mat face_img; + extractImage(images[i], req.rects[i], face_img); + images[i] = face_img; + } + } + std::vector labels(req.labels.begin(), req.labels.end()); + train(images, labels); + res.ok = true; + return true; + } catch (cv::Exception &e) { + std::stringstream ss; + ss << "error at training: " + << e.err << " " + << e.func << " " + << e.file << " " + << e.line; + res.ok = false; + res.error = ss.str(); + } + return false; + } + + void configCallback(Config &config, uint32_t level) { + boost::mutex::scoped_lock lock(mutex_); + + bool need_recreate_model = false; + bool need_retrain = false; + + use_saved_data_ = config.use_saved_data; + save_train_data_ = config.save_train_data; + face_padding_ = config.face_padding; + + if (face_model_size_.width != config.face_model_width) { + face_model_size_.width = config.face_model_width; + need_retrain = true; + } + if (face_model_size_.height != config.face_model_height) { + face_model_size_.height = config.face_model_height; + need_retrain = true; + } + + if (data_dir_ != config.data_dir) { + data_dir_ = config.data_dir; + need_retrain = true; + label_mapper_.reset(new LabelMapper()); + storage_.reset(new Storage(fs::path(data_dir_))); + } + + if (config_.model_method != config.model_method) { + need_recreate_model = true; + } + + if (config_.model_num_components != config.model_num_components) { + need_recreate_model = true; + } + + if (config.model_method == "LBPH" && ( + config_.lbph_radius != config.lbph_radius || + config_.lbph_neighbors != config.lbph_neighbors || + config_.lbph_grid_x != config.lbph_grid_x || + config_.lbph_grid_y != config.lbph_grid_y )) { + need_recreate_model = true; + } + + if (need_recreate_model) { + try { + if (config.model_method == "eigen") { + model_ = face::createEigenFaceRecognizer(config.model_num_components, + config.model_threshold); + } else if (config.model_method == "fisher") { + model_ = face::createFisherFaceRecognizer(config.model_num_components, + config.model_threshold); + } else if (config.model_method == "LBPH") { + model_ = face::createLBPHFaceRecognizer(config.lbph_radius, + config.lbph_neighbors, + config.lbph_grid_x, + config.lbph_grid_y); + } + need_retrain = true; + } catch (cv::Exception &e) { + NODELET_ERROR_STREAM("Error: create face recognizer: " << e.what()); + } + } + + if (need_retrain) { + try { + retrain(); + } catch (cv::Exception &e) { + NODELET_ERROR_STREAM("Error: train: " << e.what()); + } + } + + if (config_.model_threshold != config.model_threshold) { + try { +#if CV_MAJOR_VERSION >= 3 + if(face::BasicFaceRecognizer* model = dynamic_cast(model_.get())) { + model->setThreshold(config.model_threshold); + } else if (face::LBPHFaceRecognizer* model = dynamic_cast(model_.get())) { + model->setThreshold(config.model_threshold); + } +#else + model_->set("threshold", config.model_threshold); +#endif + } catch (cv::Exception &e) { + NODELET_ERROR_STREAM("Error: set threshold: " << e.what()); + } + } + config_ = config; + } + + void subscribe() { + NODELET_DEBUG("subscribe"); + img_sub_.subscribe(*it_, "image", 1); + face_sub_.subscribe(*nh_, "faces", 1); + if (use_async_) { + async_ = boost::make_shared >(queue_size_); + async_->connectInput(img_sub_, face_sub_); + async_->registerCallback(boost::bind(&FaceRecognitionNodelet::faceImageCallback, this, _1, _2)); + } else { + sync_ = boost::make_shared >(queue_size_); + sync_->connectInput(img_sub_, face_sub_); + sync_->registerCallback(boost::bind(&FaceRecognitionNodelet::faceImageCallback, this, _1, _2)); + } + } + + void unsubscribe() { + NODELET_DEBUG("unsubscribe"); + img_sub_.unsubscribe(); + face_sub_.unsubscribe(); + } + + public: + virtual void onInit() { + Nodelet::onInit(); + + // variables + face_model_size_ = cv::Size(190, 90); + + // dynamic reconfigures + cfg_srv_ = boost::make_shared(*pnh_); + Server::CallbackType f = boost::bind(&FaceRecognitionNodelet::configCallback, this, _1, _2); + cfg_srv_->setCallback(f); + + // parameters + pnh_->param("approximate_sync", use_async_, false); + pnh_->param("queue_size", queue_size_, 100); + + // advertise + debug_img_pub_ = advertise(*pnh_, "debug_image", 1); + face_pub_ = advertise(*pnh_, "output", 1); + train_srv_ = pnh_->advertiseService("train", + &FaceRecognitionNodelet::trainCallback, this); + it_ = boost::shared_ptr(new image_transport::ImageTransport(*nh_)); + + onInitPostProcess(); + } + }; +} + +#include +PLUGINLIB_EXPORT_CLASS(face_recognition::FaceRecognitionNodelet, nodelet::Nodelet); diff --git a/srv/FaceRecognitionTrain.srv b/srv/FaceRecognitionTrain.srv new file mode 100644 index 00000000..6c4c7882 --- /dev/null +++ b/srv/FaceRecognitionTrain.srv @@ -0,0 +1,6 @@ +sensor_msgs/Image[] images +Rect[] rects +string[] labels +--- +bool ok +string error diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 4d39cf59..8d0e7b23 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -14,6 +14,15 @@ add_custom_command(OUTPUT ${CMAKE_CURRENT_SOURCE_DIR}/vslam_tutorial.bag add_custom_target(vslam_tutorial_bag DEPENDS ${CMAKE_CURRENT_SOURCE_DIR}/vslam_tutorial.bag) add_dependencies(tests vslam_tutorial_bag) +# test data for face recognition +add_custom_command(OUTPUT ${CMAKE_CURRENT_SOURCE_DIR}/face_data + DEPENDS ${CMAKE_CURRENT_SOURCE_DIR}/face_data.tar.gz + COMMAND ${CMAKE_COMMAND} -E tar zxf face_data.tar.gz + WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} + COMMENT "Extracting face_data.tar.gz") +add_custom_target(face_data DEPENDS ${CMAKE_CURRENT_SOURCE_DIR}/face_data) +add_dependencies(tests face_data) + #add_rostest(test-apps.test) add_rostest(test-adding_images.test ARGS gui:=false) add_rostest(test-discrete_fourier_transform.test ARGS gui:=false) @@ -33,11 +42,14 @@ add_rostest(test-contour_moments.test ARGS gui:=false) if(cv_bridge_VERSION VERSION_LESS "1.11.9") # hydro skip face_detection.test elseif(OpenCV_VERSION VERSION_LESS "3.0") add_rostest(test-face_detection.test ARGS gui:=false) + add_rostest(test-face_recognition.test ARGS gui:=false) else() if(OpenCV_VERSION VERSION_LESS "3.2") add_rostest(test-face_detection.test ARGS gui:=false use_opencv3:=true use_opencv3_1:=true) + add_rostest(test-face_recognition.test ARGS gui:=false use_opencv3:=true use_opencv3_1:=true) else() add_rostest(test-face_detection.test ARGS gui:=false use_opencv3:=true use_opencv3_2:=true) + add_rostest(test-face_recognition.test ARGS gui:=false use_opencv3:=true use_opencv3_2:=true) endif() endif() add_rostest(test-goodfeature_track.test ARGS gui:=false) diff --git a/test/face_data.tar.gz b/test/face_data.tar.gz new file mode 100644 index 0000000000000000000000000000000000000000..d1a96f0b046bc41088a1ca057b5dd778f345b7e8 GIT binary patch literal 10556 zcmV-CDZ|zuiwFP?_w-i)1MHaxR8w2N#!m=cr1uu8fLI_T1O*AGG!d~=B^LoHp(7A6 z6cG_Y zVfy;|fC~JNYw2$a4?F1|s-gm%2oDVp^YQTUiun6=-gr22YZEv1qDL?fa~Cw z{1N|1{+#sn3^@72VTiT-zl(mK|9_9DUvhzO@eB6;XFp?gAwwAKf6E_g0E7Q}|HBOp z3<1tX0MkPNDtiA4gWuABc>e4@_6Q)l$I`|U0D%Ai#CZVh0bm!v1zOeWnQK+t;MFq^ zH#eA@mxq`4mxE7$pL6i>^760a7Z6+(=b6wtL7~+btBd^Qtz0}{FpnS~FQ4H5S?qd1 zj33Yfw7?)WfJ+Pn76Y-H00^f~o?qGn{b~cm1?J}A<>R!mj#Kbdl+!*K%xRj3(=lf@ znlle@i}8r7>YMXQ9B}7T3z3ALNx#FdzO%SN>fmddhQaaBcmY9a8Cf}b%?(=GIvZhd zLxj<`?YnkcSXx=z>^XG!$WaGJCua{&uM^%rzJ6gR!y_Uwr=rd#oJ%~PbRqe2#+9qr zGOypr%FWBad#|AI{)3XzvZv3=pI1~i5}KM@THD%RyyhJmzU6=b#gxsD zKwhupPR%c}fvMMSUdtj(W5!i7o|NN38ylhyJ<@_&KMH1x?+-Q}_3q8x(q!kROTX>_<0J@I}4fm^hr#sxfv@4)xZP^ysvCIP;qHKyXT z7fdR0hsyMKq>ZBTvWU%g#uSIfW4g_T*JkY%)75vB1zbB(|21Sd3-}Q0zay61{^pUw z-kS2k^!N+PprsHu{o5#C31`iPcik)MEhn!xLmG~E4@!>r^xT!)&s#v%U$*th3OS~>-1uor6Xx3NO2CMuxKp3v^|9j|1;J+@QyT<=N2mj~NAjet*{Nt2c)!~E* z7GEzmw(zTSbi!q6f3Ama>0u-NOkav_G(_m3`cF@!rh70D0)&gHDqR#5@i4qpO%7Fb(qPWVZUxZ?1;1C&~%dTH(Z61ft zO@z3uADu~ZmM(r|Ti~~3SE!j}%z%OBA{+3sv0e<^vNB~SLM(33q3W^b0hJh8@1j%Q z&5%TA%gmw%%COK`u`P1FrU?!Kxl`S>8DLu-ArHBiKy=3Prb%bs;?b1T(azmA*8syP z`6czy@rF8qDL07CmLm1pbY!IwK9$Kcdf!xzQQ6}ZzZ19;C={xXLQM^epG-?)1H$UH zrImv%dd{%Guw;N9eW)HOWU_;-n^ZQHgh<%NeKGkft|^C~cB!gp@3LxWiJ~Xi?GAmQ zSHiN4gSO>Y_Q2AQW5%8pg)ZhY9vis^#C6nr|NuE&XYH z3I)ZSZ(R}`vI)w?w&(D}hgom6s8KC}rv4SL&<$88#R%zF{=^RB*u*$QHFDJFsa;6f zXzbMXH)eVmFo<*^K%h!vb)mz}0zw^#zfRR?d+ zdH;OLA&H?&7D+Kx8wz{_>-Ti^D;`N0e^;AC(U#~-#a#RD&pvfoKq_Z{W@j? zc29SVfNQ}yrbHySuduY0Ba8ky%uM+-1=8O_XsqSC;^x9v)jyY7(TvTcBO45S9A<}h z9Y3sNa&8h8%D72UTIq@xN!j9+9DWsg$b@xduJr;oj9e%43F`Q%(k_cn!y`hrn=gsE zu6I*wlZ!#Pwt{D4A{FJ7|N07dz=tT}3pOBOs=R9iCpLh|BZy00e3k!TUXl20GRJ7^ zy@9I1i`PYQH~aSUO`M;$p@o^@$iqy{mQ8liXk2#G=p`sm2nvGqMy~rL-|_yFVR19$ zCQhG-hf|Ryh8ac9tS*wEQ=hK7*_f5AqO{4p+)B*TaW?Q&BhwD*`2PL%fG=Z~>q&7Y z8KcNJ6B%;Xx#9sQg-~quLtZd^PP41AOBfxAB-x^aD(v4Y%FiHu)07z-bsftBATAZ| zvV{1iG-z9ADXorxyeQ)ejI! zxjo@VpP4p1HH7%j{Qxm{L;Y=DH{7r!Xvt<-*tfETDe#8VUZlSvp@UmU^i&sQC29^r z$|BgOw4mJ|SUrQ<9JJ~n)zbIU^!L?rUg;Mv!!A046ScB{X{IWr#?(IL=rtLcHd|GNupIPIZ|~c$P+(h%Si|uHF`nR?c~>YE3!I zJ$flO&Lnm*j{))x*yOSEO-YJ>L`lJ2YzCdL(R3><^>t0OyuF%XTkySF>dM_16?By1 z(X5D!?XHg&KN6ZM)CZ>Aw%*3XBjv3O&lgQN2y5`zcJY7c=Hq~kW^H7mxon3ut)&HB zFtJ#)v)^UmWtkS@bD@5wMH{ch2I9kfkrK7?F+I-NctSQ}ET{1R)Wq9;ulV-Ulw=@{ zB_LiaRPuH!78xZr=7Lf)iygm#)L~s+K&G$(Z#>AE5f71cb2bkO5*ny(cfju`MP;#p z5;o9GMJ~oL@(LL7a(Az--z}S;sCt>{8Mz>}w1cidQNBuH1Hfd~I7##Ji`_OFi6)nA z8c0^oz})b_MhM8M-Q5%y9(Y$p;V2ZOLQMB5^|9d^p7dK6u6fC?i;8%R6Y~@6%4G;+ z5>$^!lanQ8&bqdw!e0A68SLUO*8=4YnL*rQ8}v8L>(jNGSR39RleXxgq#_nO6xqPm zC|$!BN+Kg{pfOqnBXL-IX|b5w!8u_fQu<=N**=U4H5o_v6?$`Yo}(g-Hue z&3_2P{~3LQ|FG}EfB0|t5C04Q_15_RJ+#LEHU583{u5fD7C~IT*25+b+xVV_4}O`3~S-Ndy<+hT>_bS5c)w_@2;$wNOT7ps&8|m*h1pwDRRMcx%-*Tv(s#7`{l*rOK zPaZ$_R9n4-d$)?UewCs(a{MWPIZriSM)+=rCrB?@UiUnl!2FbLEj3%0#0JW+pvM-A zDLQJ7CtM91^--9ZH^bs%w5eVB{T)0_p=OFNOCyE|@DU;nV^0}7A6DSzxGCeDriLh0 zqnmFC`Q%H(g*rd`GtSJXhm_cnIPo4_RN8pZcs{++=`U z=Tk>AXeh6wzN|T)$gDUUx+m1Wx4N}HRu(@Gk#)hmp}JZWxNdHY*Q zX9HgLqyhr23__?m-CD^rvMM5U@ICmi z4>$au`~NUK=o)v=ssppCWSNdZ4DPY zwimp}n>yCjU>~>024q>fE|bpr_Y~acUc7&>O|6Cvw8lzSZ(c^awvHgdeZIww`MYOJ zV(4A_%0P1kEkXUgL_&^8s%OdiEyLGGe@1_-lOcU_ld2$H+gF(S^FWltFhqfQ+Vlqb zIb2~%J5ZXADAY3ItycD}R;LTU8Q)j^y69rQvX}@Y8whr`N>-(N$CE4gwkn=>jeIGU zeHU}|OJgR2gw>Ne+iApiQD`wY&h*Pl+`@WZ5s6MxYIV?tLGh`KOfgp{M)^+vC|IWX-J(N}8O<3%o8{k#4qI$QL#I9D4tyUrdi1^c_6fYcrX4 zxVu&4Md1nA)}GnNR=Y1-T2rtsZ(=);dw}s6&9aRem^{GLUTLC`wb8^d1Ae0|{8)Vi zZ2y0;bFcAC|9>CAzY-E!2j_Dr2`%T8OurKHFH)J%kP6MIgkd%&<~)Z&Q_E()#mBo0*h1pLIahS5R1ClFD~#B~!s3SzWJ@Ab@pcahx*ap=KbF{I zzHw^*cg$b-e{engH!#xwH~)1v{9niX3jS}L|Nl1re@Dl0RX>pY#zfw^L+=%5&(m^; z`_s=MoJO(nNZaW^ze3BDO~NS;Ej&P8`pa|TT~e&me1=fj(qpn5 zs;>tDw@YtY6})>@;{F*sJ=usGW{MunU9`kd^$7b8?})p6)ac1#WEoSaDZ9A7<@>PX z%K_AsG@d{Tq0gN*Ifyh5FS(~ZFBL@VC8=LvWzsG=*@bBk>JZ12b%KERLaE%hWJLpV z1X=DDUaBoXOJ!tEB%)>0%W>JYPDagKJ%j4VXw7|WNc1k5Z<2}CdvbDIYz@xzpm#T; zK`zs1Mw(}evRlXZ*@p~j3r=~;#wX-3B=ku+Z2~| z*=qb#c~C~jDy5Mu3AsuYfyBCJbl_IUB1x0@b1vl&f>84}$r+>7j5@J+Vnpmg&Hj{! z>Jlqd_BmF9UBV^YAMZyUu7()i16q$x@q_3dui)C?(JHq`#)Faa%J<#n7hE)*IqD2p zahXi<)BUun&eP%i%x-#qG7`d=X=|Q5Tb=b7u}6G-H4Q%L1eSsgQ*&nPZkxi9?T5Dl zQvg;IDhb#h0bGyn~^KfLM9mI&#vzD4O+8TRZ+f=(+M?;w z0(QAF4xy)Q45|FKvAy2}H+KvCdg&mQ9KzC${$gqqD=>i408BT_s7)7#0F>C5}xB$zeu$5lVVj*J1_&``=)cdK08OXP`Z z?fyjZ+z0nljGshVlj>xzR!P~RAK8pSKL1_X(0}@`^Zz{msbgUDU-O>^KmXd8|6GUs z`TPItcOCbCe)hgU@BeI^|Ex0K1L$W(~uu$`~3RoObVIv67&qelh*@Uh>=WYct!DrV>f2y8^5}T>rZ&AoH zTq+IH&Ogc|_$nNpR2qYM(80+N(FSR1LmXWsq|mTuF1B^pY%I}Muq~M*RM1?qmIt@I zDR}Taw2KGqH05LMa_~Ct6`Q>Bww&_3acqn!)SS*rd*iNs=Ss-Uyca+4`AuQrGT#W66sIh#pRuJgv?ISB_DRD8Mm9?uK zpN0&toXJ##q&tv%)yaL2pUE^c9*4>YzXon`_w*3RSh9e656O5-{LUy3io|#AHEhcx zgP=@{y@=vF&y9Y-dr^j*fc~Psu4u2v1VfBFQQEfy!mXVo$c3R5 zjR%Y>6fcfwV0eI|x$eL#YrSo^nJ^j;5LO^_I9wtGivUnKl;_^^tBn$|C=Zm#o-haE@^`EgcQ#a>=z41aW%z+$scvfxdQ;a?SHdi?On=)K=(bfV+J z$*N{Du){Sy^!h6qAC0%>6~n96Vvrt1NcFYiTQ1UGXS1S*bB?@F8HHq-ZH}CRw~=I? z%((1AszVYM7t@^F(jLEUS6s?vfaw#dK5R2jn0!OOq+z;4wCV-tv=P^3eLi+7-A2*L z+#4sJ^*QQeJc9>FAZU4N$Bbzfq5Js1kTD}-HN6cx2M`W5+nqMcL(@>bXc59*i~~OY zwP+lB6f1`%SB7Gn^W`0_X^4SK(gQ8qKqZ=uXn$e9@)sCb90XtzK1SH9W^u%DxPE|#$@bF#s(2=Q;j@5i+kCuc zZUVG=V3&V8;O|)g%GEB4Z==npKN;w1GWJ$ou#}%vjA`&^MX@b9;B;aAMZ$rPHCk?I zc2@s32rDxm4j+bG&eGq^yn@=#EXnJ!-cu2t z;f-Cv$?OjJW-iXRxHi|~k00{6riFWxwuK(QuK@HbBKiyGFZ^GZ`=9#%dnLK}EMqZP@VmOmu2T-b|}FMix>KDw0cw3LEO(inouuZ4L~i6O}q zOg0T2Q904~%|PUl@2H&W`KEHE(i>)y4SNtu&DRDRj~1P=Y}Pmi6Jd(bq%cI!J>1gzS=4=`9%s*VWvXMklND;5+S}k!t(vcw{1hB#9n;%x={=_VNIXFVc*{ z1FqqRh9JVn%iq+VdAd2JL+W0%x{`+KgGO%PDvk$;c%r*|c>wjo$^{11T7-Rk3Z-J% z=&(EOr1zq-DD=b6YC{C0Cri0U%@lEL8>C?$M~8h8?pWKzfBoaM=D}~RV#qnR8Aq7q z@px9G0`WjnzFmjNa9$0gP|!7>vQ1N&Hvg!NXC&k#SQ%|P?3%p9gucFHZJ*QT{~0#W z{m5|$XL#b|t7EffvOGXiKS4+uaIB0$kJ~%{G#7DJw8`sj_;+&Ff|W zl^C3_V0w@`6B^R1O|*XTxU$_%(n>kCZ}CY$qwKq`d$fVc1eCfr=Ch6I9lk*%xc3_Y zC*hb=5ffNVaQ)6sJA{YwfZK%>E-G^YuUgd)*7kvo$AI>YO<&*vHB0D~nMJ-OG)KH* zxsBnG4DsXvAdW68to*pq^7XFl+}`BpH;DY9fjmI*!^99Ykr0;ovTtcxfHa>Khn z&*{FBg{B&hLwl4M=i3-HuOUf!qKwTo+*{e=x-hEK{_))_r!WC?eM(7)?pU-ZC`U$xee-%1zl==wk5}9rLIVy^x z+DGANE~{T)P9=|9h>t!p<9i1naC7$<8I)6Ng+9oT#9SBa?^NYH=%xlU)(U$+>v#)H z+2`{7Ql*NXuv)XL&O1~Lin=NqSKyhayKA3hr(5Gp9rin&e5AnyL3Zdjv34(+S?K(j zbm&vnCMy@%5nF+8i7u5%3*+7#*%ukPd!=PJve`rds7n#no*abEeoZ=gt6nHor)iqZ{##Q(FyT;&1L znKfhyj`4#*=eo6YyJWgOsC`FnTlyltSKFc`t+MsCd$jFgO1l!{G#+cZn`se0Z@Pzo zo(i%hY_t4wug&jG!^4l2^MVDV{Ec5d`THTG#Z`nD_c2_@Y#z^r_S|aZzZD zGpkz8Snfpc6+r`ZRx+m6FCq8`^qSS)yS2AOZ@`WOYQ;&s>-4>lY6aYyHd88xFsyjM z5OkE1WGYTY$}_$;Dedr*(hA&CtSpxjGLlztOBJs$OI@1EWLtH0_mahVfGZD>L*Qun zZQ81@M|Sng%Dt^WX7?rMZmL7X`Q$_Rp%_xe>Y@3G3!l|ay^CzM{6Fs;f8qc7y#J(g z@IUW=>KShMzb^R|{NGsr|2F=!DrokZflLTpD(9A?#mhR6yUA9UoeWm381ADU(Hu>h z^rq>j_h8D-wW4`PXD4y2z4>1|L{W-L5=iHVm*4zcc_(2X%)qC>@eo3AGlXyW?Ug*W zlo6eQ2jT)ajwio5UHvvvOWp8?EOMv7QPIn!zO#(vTw3n6;Wn6cJ1z1E&vVsMdvG3lEN6! zV@#8Pv>%7BoV?VQJ1mHH^y6qP^ME`aP>Eb%fSgJ1Q39T_CYhFBv@+eyUu`{U_G1-F_3@tfPrL2Mb_ZaQGP7OT(A0r?$ z?2sK4Dfe+0B3#9yTX}TQIhrh1Owx`#xX7?fO70t09CEihaDKTSU60Q7dHx6A?=P><=kfh~-=CR~l+v3UOCT{hJy=J` z%NG^~S$B!x51f9Evb#}Zi02_CC-yuhce}>9G#yxcLorTBH!0+Ug zR6w|soYy`wu~Auq{L0j(*a|o|f|_EFG2S9pqR6-4)?W$#V2n^(XLb|Gvu5rq~b88GWRH9A?+(&)cxyD4@P->{1WuR*d+I{Br-_ z@dy3?Ec2iC*gO1N|DFG}|91ra{~W%A{)6*>f13WUn#k4JQ^y0RCUjGhbt4L%8;>Ay z_?x+{M7!Sov!m@R%YG8&D#GrG5!x^}v3|HgE!22X&6-WRs7_WTCP`K%qEx?q;G=*x zl{&nrJs7(8KmqIqlh1vG)Jq;h!Q@7P1EG89(S~o-?;Ar_=5B3+DyS{(sEMBJeu7`d zt9L)3uMt){<@y~TZER!TH@ldqswT!Q@=%+3{t-nWrW)&mb;!h|rC8Z+^FYwIleg3Ni1?1;f? z%SVDYt?z8}Y}TXp6Kj|F1gWNFlzGOe@2J6*82fTd<*D&((x%9LyF`;dy1lo*Yr`34 z23Koq5Rmg0QYVRSPhkG=5?vgo;#i>RjOL)4UQzEx*b#yS-gj)xuKTv1u{25}Vx=Ag zGG@f7?zsEvsSh^Qt@>GzS6HRS+xX5Bi)*Ctx(;|3OtrOTo2lCXLPS$QofxKe&@;!k zVUzCByVH`}SJ4eJqNFXFCJB>SQ)lBFFe=;b#D=yg>*>z~y9rl8}@dJz?X;AIRy#C$yMMW{E`|A!q$;oSdO1B*% z8vY_^HjhO5J#1+l|G1A0`3$1HMHloc4qiHclfuK@T3_aHa>lUZhj0x&Ne-0;R?qeu ztom-8X_?EEo|V~2(86PV6KP{<*4R@Qw+x)2vO+5uUQb`aXM$5mKMq{i^meL$PU%0P zOTO471Q+mf#2KgTM&PS^U9q#mSYaGn|6;`@r zbnF8qs6%9tO3pd`DIX_aLPJ@LZP=`m<8r21S}zS|ZNI;Ix_o%U>VniZdC1x5YXx); zzL}7^d`{}c*4|rq>F;F(Q~CO;LjHnV&CpvbYqZ&Uai#J~7G$SXWV+##0$QrAgzs1@ z+h-C+mASSE+wRo*#%uPu(%sjn3=N`_d{{oj8Pz#RA?dxkFfhj!h3&%&OJ1BVoU8BY zVR)BUi|-jtj`U?NA-8eeMy{>iYKQX%UXheX*wG| zR?N*t)|?-Qg)|B4hsq6&c}Mm5rgs-TQ0WS&7JascKtFQZFM*B=pv7{{Eyy$--;Fnk zA?!x;kzj$%seljtFv2gSheqAlv}6N`D12f(Bij*sA!jW$TrU%6p&W0pW_c&Yy;U@J zRU=Ec+3NjN%wvP;OW;N)00000000000000000000000000000000000007|s*gpV| KH7N`Lpa1}8)HmD! literal 0 HcmV?d00001 diff --git a/test/test-face_recognition.test b/test/test-face_recognition.test new file mode 100644 index 00000000..fd8a1b21 --- /dev/null +++ b/test/test-face_recognition.test @@ -0,0 +1,32 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +