-
Notifications
You must be signed in to change notification settings - Fork 70
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Merge pull request #63 from furushchev/face-recognition-new
[face_recognition] add nodelet / script / message files for face recognition (new)
- Loading branch information
Showing
11 changed files
with
824 additions
and
3 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -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")) |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,41 @@ | ||
<launch> | ||
<arg name="launch_face_detection" default="true" /> | ||
<arg name="launch_trainer" default="true" /> | ||
|
||
<arg name="use_opencv3" default="false" /> | ||
<arg name="use_opencv3_1" default="false" /> | ||
<arg name="use_opencv3_2" default="false" /> | ||
<arg name="debug_view" default="true" /> | ||
|
||
<arg name="image" default="image" /> | ||
<arg name="data_dir" default="~/.ros/opencv_apps/face_data" /> | ||
|
||
<include file="$(find opencv_apps)/launch/face_detection.launch" | ||
if="$(arg launch_face_detection)"> | ||
<arg name="image" value="$(arg image)" /> | ||
<arg name="debug_view" value="$(arg debug_view)" /> | ||
<arg name="node_name" value="face_detection" /> | ||
<arg name="use_opencv3" value="$(arg use_opencv3)" /> | ||
<arg name="use_opencv3_1" value="$(arg use_opencv3_1)" /> | ||
<arg name="use_opencv3_2" value="$(arg use_opencv3_2)" /> | ||
</include> | ||
|
||
<node name="face_recognition" pkg="opencv_apps" type="face_recognition" | ||
output="screen"> | ||
<param name="data_dir" value="$(arg data_dir)" /> | ||
<remap from="image" to="$(arg image)" /> | ||
<remap from="faces" to="face_detection/faces" /> | ||
</node> | ||
|
||
<node name="face_recognition_trainer" pkg="opencv_apps" type="face_recognition_trainer.py" | ||
if="$(arg launch_trainer)" launch-prefix="xterm -fn 12x24 -e" respawn="true"> | ||
<remap from="image" to="$(arg image)" /> | ||
<remap from="faces" to="face_detection/faces" /> | ||
<remap from="train" to="face_recognition/train" /> | ||
</node> | ||
|
||
<node name="$(anon debug_image_viewer)" pkg="image_view" type="image_view" | ||
if="$(arg debug_view)"> | ||
<remap from="image" to="face_recognition/debug_image" /> | ||
</node> | ||
</launch> |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,2 +1,4 @@ | ||
Rect face | ||
Rect[] eyes | ||
string label | ||
float64 confidence |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -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() |
Oops, something went wrong.