Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 from __future__ import print_function
00036
00037 try:
00038 input = raw_input
00039 except:
00040 pass
00041
00042 import rospy
00043 import message_filters
00044 from sensor_msgs.msg import Image
00045 from opencv_apps.msg import FaceArrayStamped
00046 from opencv_apps.srv import FaceRecognitionTrain, FaceRecognitionTrainRequest
00047
00048 class FaceRecognitionTrainer(object):
00049 def __init__(self):
00050 self.queue_size = rospy.get_param("~queue_size", 100)
00051
00052 self.img_sub = message_filters.Subscriber("image", Image)
00053 self.face_sub = message_filters.Subscriber("faces", FaceArrayStamped)
00054
00055 self.req = FaceRecognitionTrainRequest()
00056 self.label = ""
00057 self.ok = False
00058
00059 self.sync = message_filters.TimeSynchronizer([self.img_sub, self.face_sub],
00060 self.queue_size)
00061 self.sync.registerCallback(self.callback)
00062 def callback(self, img, faces):
00063 if len(faces.faces) <= 0:
00064 return
00065 if self.ok:
00066 faces.faces.sort(key=lambda f: f.face.width * f.face.height)
00067 self.req.images.append(img)
00068 self.req.rects.append(faces.faces[0].face)
00069 self.req.labels.append(self.label)
00070 self.ok = False
00071 def run(self):
00072 rospy.wait_for_service("train")
00073 train = rospy.ServiceProxy("train", FaceRecognitionTrain)
00074 self.label = input("Please input your name and press Enter: ")
00075 while len(self.label) <= 0 or input("Your name is %s. Correct? [y/n]: " % self.label) not in ["", "y", "Y"]:
00076 self.label = input("Please input your name and press Enter: ")
00077
00078 input("Please stand at the center of the camera and press Enter: ")
00079 while True:
00080 self.ok = True
00081 while self.ok:
00082 print("taking picture...")
00083 rospy.sleep(1)
00084 if input("One more picture? [y/n]: ") not in ["", "y", "Y"]:
00085 break
00086 print("sending to trainer...")
00087
00088 res = train(self.req)
00089 if res.ok:
00090 print("OK. Trained successfully!")
00091 else:
00092 print("NG. Error: %s" % res.error)
00093
00094 if __name__ == '__main__':
00095 rospy.init_node("face_recognition_trainer")
00096 t = FaceRecognitionTrainer()
00097 t.run()