4 import cv2, os, time, base64, urllib2, rospy
7 from xbot_face.msg
import FaceResult
8 from std_msgs.msg
import String, UInt32
9 from sensor_msgs.msg
import Image
10 from cv_bridge
import CvBridge, CvBridgeError
12 url =
"http://192.168.8.141:8000/recognition" 17 """docstring for face_recog""" 20 self.
face_result_pub = rospy.Publisher(
'/xbot/face_result',FaceResult,queue_size=1)
21 rospy.Subscriber(
'/xbot/camera/image', Image, self.
imageCB)
30 cv_image = self.bridge.imgmsg_to_cv2(msg,
"bgr8")
31 except CvBridgeError
as e:
34 result_msg = FaceResult()
35 cv2.imwrite(
'tmp.jpg',cv_image)
36 with open(
"tmp.jpg",
"rb")
as fp:
37 image_binary = fp.read()
38 image_binary = base64.b64encode(image_binary)
39 post_data = {
"Image":image_binary}
40 body = JSONEncoder().encode(post_data)
41 req = urllib2.Request(url, body)
42 response = urllib2.urlopen(req).read()
43 body = JSONDecoder().decode(response)
47 if body[
'Id'] ==
'UNKNOWN' or body[
'Id'] ==
'None':
48 result_msg.face_exist = 0
49 result_msg.name = body[
'Id']
50 result_msg.confidence = 0
51 self.face_result_pub.publish(result_msg)
55 result_msg.face_exist = 1
56 result_msg.name = body[
'Id']
57 result_msg.confidence = body[
'Confidence']
58 self.face_result_pub.publish(result_msg)
69 if __name__ ==
'__main__':
70 rospy.init_node(
'face_recog')
72 rospy.loginfo(
'face recogition initialized...')
74 except rospy.ROSInterruptException:
75 rospy.loginfo(
'face recogition initialize failed, please retry...')