Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[face_recognition] add nodelet / script / message files for face recognition #41

Closed
wants to merge 9 commits into from
22 changes: 20 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,7 +1,16 @@
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
image_transport
message_generation
nodelet
roscpp
sensor_msgs
std_msgs
)

find_package(OpenCV REQUIRED)
message(STATUS "OpenCV Components: ${OpenCV_LIB_COMPONENTS}")
Expand All @@ -23,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/CamShift.cfg
Expand Down Expand Up @@ -55,6 +65,7 @@ add_message_files(
Face.msg
FaceArray.msg
FaceArrayStamped.msg
Label.msg
Line.msg
LineArray.msg
LineArrayStamped.msg
Expand All @@ -73,10 +84,16 @@ add_message_files(
ContourArrayStamped.msg
)

add_service_files(
FILES
FaceRecognitionTrain.srv
)

## Generate added messages and services with any dependencies listed here
generate_messages(
DEPENDENCIES
std_msgs
sensor_msgs
)

catkin_package(CATKIN_DEPENDS std_msgs
Expand Down Expand Up @@ -238,6 +255,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
Expand Down Expand Up @@ -328,7 +346,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)

Expand Down
59 changes: 59 additions & 0 deletions cfg/FaceRecognition.cfg
Original file line number Diff line number Diff line change
@@ -0,0 +1,59 @@
#! /usr/bin/env python
# Software License Agreement (BSD License)
#
# Copyright (c) 2014, Kei Okada.
# 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_padding", int_t, 0, "Padding on face", 0, -30, 30)
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"))
37 changes: 37 additions & 0 deletions launch/face_recognition.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
<launch>
<arg name="launch_face_detection" default="true" />
<arg name="launch_trainer" default="true" />

<arg name="use_opencv3" 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)" />
</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>
1 change: 1 addition & 0 deletions msg/Face.msg
Original file line number Diff line number Diff line change
@@ -1,2 +1,3 @@
Rect face
Rect[] eyes
Label label
2 changes: 2 additions & 0 deletions msg/Label.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
string name
float64 confidence
4 changes: 4 additions & 0 deletions nodelet_plugins.xml
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,10 @@
<description>Nodelet to find faces</description>
</class>

<class name="face_recognition/face_recognition" type="face_recognition::FaceRecognitionNodelet" base_class_type="nodelet::Nodelet">
<description>Nodelet to identify faces</description>
</class>

<class name="goodfeature_track/goodfeature_track" type="goodfeature_track::GoodfeatureTrackNodelet" base_class_type="nodelet::Nodelet">
<description>Nodelet for detecting corners using Shi-Tomasi method</description>
</class>
Expand Down
99 changes: 99 additions & 0 deletions scripts/face_recognition_trainer.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,99 @@
#! /usr/bin/env python
# Software License Agreement (BSD License)
#
# Copyright (c) 2014, Kei Okada.
# 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.
#
# Author: Yuki Furuta <furushchev@jsk.imi.i.u-tokyo.ac.jp>


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()
Loading