scripts
face_recognition_trainer.py
Go to the documentation of this file.
1
#! /usr/bin/env python
2
# Software License Agreement (BSD License)
3
#
4
# Copyright (c) 2017, Yuki Furuta.
5
# All rights reserved.
6
#
7
# Redistribution and use in source and binary forms, with or without
8
# modification, are permitted provided that the following conditions
9
# are met:
10
#
11
# * Redistributions of source code must retain the above copyright
12
# notice, this list of conditions and the following disclaimer.
13
# * Redistributions in binary form must reproduce the above
14
# copyright notice, this list of conditions and the following
15
# disclaimer in the documentation and/or other materials provided
16
# with the distribution.
17
# * Neither the name of Kei Okada nor the names of its
18
# contributors may be used to endorse or promote products derived
19
# from this software without specific prior written permission.
20
#
21
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32
# POSSIBILITY OF SUCH DAMAGE.
33
34
35
from
__future__
import
print_function
36
37
try
:
38
input = raw_input
39
except
:
40
pass
41
42
import
rospy
43
import
message_filters
44
from
sensor_msgs.msg
import
Image
45
from
opencv_apps.msg
import
FaceArrayStamped
46
from
opencv_apps.srv
import
FaceRecognitionTrain, FaceRecognitionTrainRequest
47
48
class
FaceRecognitionTrainer
(object):
49
def
__init__
(self):
50
self.
queue_size
= rospy.get_param(
"~queue_size"
, 100)
51
52
self.
img_sub
=
message_filters.Subscriber
(
"image"
, Image)
53
self.
face_sub
=
message_filters.Subscriber
(
"faces"
, FaceArrayStamped)
54
55
self.
req
= FaceRecognitionTrainRequest()
56
self.
label
=
""
57
self.
ok
=
False
58
59
self.
sync
=
message_filters.TimeSynchronizer
([self.
img_sub
, self.
face_sub
],
60
self.
queue_size
)
61
self.
sync
.registerCallback(self.
callback
)
62
def
callback
(self, img, faces):
63
if
len(faces.faces) <= 0:
64
return
65
if
self.
ok
:
66
faces.faces.sort(key=
lambda
f: f.face.width * f.face.height)
67
self.
req
.images.append(img)
68
self.
req
.rects.append(faces.faces[0].face)
69
self.
req
.labels.append(self.
label
)
70
self.
ok
=
False
71
def
run
(self):
72
rospy.wait_for_service(
"train"
)
73
train = rospy.ServiceProxy(
"train"
, FaceRecognitionTrain)
74
self.
label
=
input
(
"Please input your name and press Enter: "
)
75
while
len(self.
label
) <= 0
or
input
(
"Your name is %s. Correct? [y/n]: "
% self.
label
)
not
in
[
""
,
"y"
,
"Y"
]:
76
self.
label
=
input
(
"Please input your name and press Enter: "
)
77
78
input
(
"Please stand at the center of the camera and press Enter: "
)
79
while
True
:
80
self.
ok
=
True
81
while
self.
ok
:
82
print(
"taking picture..."
)
83
rospy.sleep(1)
84
if
input
(
"One more picture? [y/n]: "
)
not
in
[
""
,
"y"
,
"Y"
]:
85
break
86
print(
"sending to trainer..."
)
87
88
res = train(self.
req
)
89
if
res.ok:
90
print(
"OK. Trained successfully!"
)
91
else
:
92
print(
"NG. Error: %s"
% res.error)
93
94
if
__name__ ==
'__main__'
:
95
rospy.init_node(
"face_recognition_trainer"
)
96
t =
FaceRecognitionTrainer
()
97
t.run()
face_recognition_trainer.FaceRecognitionTrainer.face_sub
face_sub
Definition:
face_recognition_trainer.py:53
face_recognition_trainer.FaceRecognitionTrainer.run
def run(self)
Definition:
face_recognition_trainer.py:71
face_recognition_trainer.FaceRecognitionTrainer.callback
def callback(self, img, faces)
Definition:
face_recognition_trainer.py:62
face_recognition_trainer.FaceRecognitionTrainer.label
label
Definition:
face_recognition_trainer.py:56
face_recognition_trainer.FaceRecognitionTrainer.req
req
Definition:
face_recognition_trainer.py:55
face_recognition_trainer.FaceRecognitionTrainer.ok
ok
Definition:
face_recognition_trainer.py:57
face_recognition_trainer.FaceRecognitionTrainer.img_sub
img_sub
Definition:
face_recognition_trainer.py:52
face_recognition_trainer.input
input
Definition:
face_recognition_trainer.py:38
face_recognition_trainer.FaceRecognitionTrainer.sync
sync
Definition:
face_recognition_trainer.py:59
face_recognition_trainer.FaceRecognitionTrainer.__init__
def __init__(self)
Definition:
face_recognition_trainer.py:49
face_recognition_trainer.FaceRecognitionTrainer
Definition:
face_recognition_trainer.py:48
face_recognition_trainer.FaceRecognitionTrainer.queue_size
queue_size
Definition:
face_recognition_trainer.py:50
message_filters::TimeSynchronizer
message_filters::Subscriber
opencv_apps
Author(s): Kei Okada
autogenerated on Thu Feb 2 2023 03:40:24