|
| 1 | +#!/usr/bin/env python |
| 2 | +import datetime |
| 3 | +import os |
| 4 | +import sys |
| 5 | + |
| 6 | +import cv2 |
| 7 | +import rospy |
| 8 | +from cv_bridge import CvBridge, CvBridgeError |
| 9 | +from image_recognition_msgs.msg import FaceProperties |
| 10 | +from image_recognition_msgs.srv import GetFaceProperties |
| 11 | +from image_recognition_util import image_writer |
| 12 | +from keras_ros.age_gender_estimator import AgeGenderEstimator |
| 13 | + |
| 14 | + |
| 15 | +class WideResnetFaceProperties: |
| 16 | + def __init__(self, weights_file_path, img_size, depth, width, save_images_folder): |
| 17 | + """ |
| 18 | + ROS node that wraps the Wide Resnet age gender estimator |
| 19 | + """ |
| 20 | + self._bridge = CvBridge() |
| 21 | + self._properties_srv = rospy.Service('get_face_properties', GetFaceProperties, self._get_face_properties_srv) |
| 22 | + self._estimator = AgeGenderEstimator(weights_file_path, img_size, depth, width) |
| 23 | + |
| 24 | + if save_images_folder: |
| 25 | + self._save_images_folder = os.path.expanduser(save_images_folder) |
| 26 | + if not os.path.exists(self._save_images_folder): |
| 27 | + os.makedirs(self._save_images_folder) |
| 28 | + else: |
| 29 | + self._save_images_folder = None |
| 30 | + |
| 31 | + rospy.loginfo("WideResnetFaceProperties node initialized:") |
| 32 | + rospy.loginfo(" - weights_file_path=%s", weights_file_path) |
| 33 | + rospy.loginfo(" - img_size=%s", img_size) |
| 34 | + rospy.loginfo(" - depth=%s", depth) |
| 35 | + rospy.loginfo(" - width=%s", width) |
| 36 | + rospy.loginfo(" - save_images_folder=%s", save_images_folder) |
| 37 | + |
| 38 | + def _get_face_properties_srv(self, req): |
| 39 | + """ |
| 40 | + Callback when the GetFaceProperties service is called |
| 41 | + :param req: Input images |
| 42 | + :return: properties |
| 43 | + """ |
| 44 | + # Convert to opencv images |
| 45 | + try: |
| 46 | + bgr_images = [self._bridge.imgmsg_to_cv2(image, "bgr8") for image in req.face_image_array] |
| 47 | + except CvBridgeError as e: |
| 48 | + raise Exception("Could not convert image to opencv image: %s" % str(e)) |
| 49 | + |
| 50 | + rospy.loginfo("Estimating the age and gender of %d incoming images ...", len(bgr_images)) |
| 51 | + estimations = self._estimator.estimate(bgr_images) |
| 52 | + rospy.loginfo("Done") |
| 53 | + |
| 54 | + face_properties_array = [] |
| 55 | + for (age, gender) in estimations: |
| 56 | + face_properties_array.append(FaceProperties( |
| 57 | + age=int(age), |
| 58 | + gender=FaceProperties.FEMALE if gender[0] > 0.5 else FaceProperties.MALE, |
| 59 | + )) |
| 60 | + |
| 61 | + # Store images if specified |
| 62 | + if self._save_images_folder: |
| 63 | + def _get_label(p): |
| 64 | + return "age_%d_gender_%s" % (p.age, "male" if p.gender == FaceProperties.MALE else "female") |
| 65 | + |
| 66 | + image_writer.write_estimations(self._save_images_folder, bgr_images, |
| 67 | + [_get_label(p) for p in face_properties_array], |
| 68 | + suffix="_face_properties") |
| 69 | + |
| 70 | + # Service response |
| 71 | + return {"properties_array": face_properties_array} |
| 72 | + |
| 73 | +if __name__ == '__main__': |
| 74 | + rospy.init_node("face_properties") |
| 75 | + |
| 76 | + try: |
| 77 | + weights_file_path = rospy.get_param("~weights_file_path") |
| 78 | + img_size = rospy.get_param("~image_size", 64) |
| 79 | + depth = rospy.get_param("~depth", 16) |
| 80 | + width = rospy.get_param("~width", 8) |
| 81 | + save_images = rospy.get_param("~save_images", True) |
| 82 | + |
| 83 | + save_images_folder = None |
| 84 | + if save_images: |
| 85 | + save_images_folder = rospy.get_param("~save_images_folder", "/tmp/keras_ros") |
| 86 | + except KeyError as e: |
| 87 | + rospy.logerr("Parameter %s not found" % e) |
| 88 | + sys.exit(1) |
| 89 | + |
| 90 | + try: |
| 91 | + WideResnetFaceProperties(weights_file_path, img_size, depth, width, save_images_folder) |
| 92 | + rospy.spin() |
| 93 | + except Exception as e: |
| 94 | + rospy.logfatal(e) |
| 95 | + |
0 commit comments