35 from __future__ 
import print_function
 
   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
 
   55         self.
req = FaceRecognitionTrainRequest()
 
   63         if len(faces.faces) <= 0:
 
   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)
 
   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: ")
 
   78         input(
"Please stand at the center of the camera and press Enter: ")
 
   82                 print(
"taking picture...")
 
   84             if input(
"One more picture? [y/n]: ") 
not in [
"", 
"y", 
"Y"]:
 
   86         print(
"sending to trainer...")
 
   90             print(
"OK. Trained successfully!")
 
   92             print(
"NG. Error: %s" % res.error)
 
   94 if __name__ == 
'__main__':
 
   95     rospy.init_node(
"face_recognition_trainer")