|
1 | 1 | #!/usr/bin/env python |
2 | 2 |
|
| 3 | +import os |
| 4 | +import sys |
| 5 | + |
| 6 | +import diagnostic_updater |
3 | 7 | import rospy |
4 | 8 | from cv_bridge import CvBridge, CvBridgeError |
5 | | - |
6 | | -from image_recognition_msgs.srv import Recognize, Annotate |
7 | 9 | from image_recognition_msgs.msg import Recognition, Recognitions, CategoryProbability, CategoricalDistribution |
| 10 | +from image_recognition_msgs.srv import Recognize, Annotate |
| 11 | +from image_recognition_util import image_writer |
| 12 | +from openface_ros.face_recognizer import FaceRecognizer |
8 | 13 | from sensor_msgs.msg import RegionOfInterest, Image |
9 | 14 | from std_srvs.srv import Empty |
10 | 15 |
|
11 | | -import os |
12 | | -import sys |
13 | | - |
14 | | -from image_recognition_util import image_writer |
15 | | -from openface_ros.face_recognizer import FaceRecognizer, RecognizedFace |
16 | | - |
17 | 16 |
|
18 | 17 | class OpenfaceROS: |
19 | 18 | def __init__(self, align_path, net_path, save_images_folder, topic_save_images, |
@@ -74,8 +73,8 @@ class OpenfaceROS: |
74 | 73 | raise Exception("Could not convert to opencv image: %s" % str(e)) |
75 | 74 |
|
76 | 75 | for annotation in req.annotations: |
77 | | - roi_image = bgr_image[annotation.roi.y_offset:annotation.roi.y_offset+annotation.roi.height, |
78 | | - annotation.roi.x_offset:annotation.roi.x_offset + annotation.roi.width] |
| 76 | + roi_image = bgr_image[annotation.roi.y_offset:annotation.roi.y_offset + annotation.roi.height, |
| 77 | + annotation.roi.x_offset:annotation.roi.x_offset + annotation.roi.width] |
79 | 78 |
|
80 | 79 | if self._save_images_folder: |
81 | 80 | image_writer.write_annotated(self._save_images_folder, roi_image, annotation.label, True) |
@@ -183,8 +182,8 @@ class OpenfaceROS: |
183 | 182 | def restore_trained_faces(self, file_name): |
184 | 183 | self._face_recognizer.restore_trained_faces(file_name) |
185 | 184 |
|
186 | | -if __name__ == '__main__': |
187 | 185 |
|
| 186 | +if __name__ == '__main__': |
188 | 187 | rospy.init_node("face_recognition") |
189 | 188 |
|
190 | 189 | try: |
@@ -216,4 +215,9 @@ if __name__ == '__main__': |
216 | 215 | rospy.loginfo('loading face database from %s', db) |
217 | 216 | openface_ros.restore_trained_faces(db) |
218 | 217 |
|
| 218 | + updater = diagnostic_updater.Updater() |
| 219 | + updater.setHardwareID("none") |
| 220 | + updater.add(diagnostic_updater.Heartbeat()) |
| 221 | + rospy.Timer(rospy.Duration(1), lambda event: updater.force_update()) |
| 222 | + |
219 | 223 | rospy.spin() |
0 commit comments