aws_auto_checkin_app.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 
11 
12 from __future__ import division
13 
14 import rospy
15 
16 import message_filters
17 from sensor_msgs.msg import CompressedImage, Image
18 from opencv_apps.msg import FaceArrayStamped, Face, Rect
19 from jsk_recognition_msgs.msg import RectArray
20 from jsk_recognition_msgs.msg import ClassificationResult
21 
22 import numpy as np
23 
24 import boto3
25 import cv2
26 from cv_bridge import CvBridge
27 import datetime
28 import json
29 import requests
30 import math
31 import sys
32 
33 from jsk_topic_tools import ConnectionBasedTransport
34 
35 
36 class AutoCheckIn(ConnectionBasedTransport):
37 
38  def __init__(self):
39  super(AutoCheckIn, self).__init__()
40 
41  env_path = rospy.get_param('~env_path', 'env.json')
42  rospy.loginfo("Loading AutoCheckin env variables from {}".format(env_path))
43  try:
44  with open(env_path) as env_json:
45  env = json.load(env_json)
46  except IOError:
47  rospy.logerr('Cannot open "{}".\nCopy "default.env.json" file as a new file called "env.json" and edit parameters in it.'.format(env_path))
48  sys.exit(1)
49 
50  try:
51  self.FACE_AREA_THRESHOLD = env['FaceAreaThreshold']
52  self.FACE_SIMILARITY_THRESHOLD = env['FaceSimilarityThreshold']
53  self.COLLECTION_ID = env['CollectionId']
54  self.DYNAMODB_TABLE = env['DynamodbTable']
55  self.MAX_FACES = env['MaxFaces']
56  region_name = env['Region']
57  except KeyError:
58  print('Invalid config file')
59  raise
60 
61  aws_credentials_path = rospy.get_param('~aws_credentials_path', 'aws.json')
62  rospy.loginfo("Loading AWS credentials from {}".format(aws_credentials_path))
63  try:
64  with open(aws_credentials_path) as aws_json:
65  aws_credentials = json.load(aws_json)
66  except IOError:
67  rospy.logerr('Cannot open "{}".\n Please put region/aws_access_key_id/aws_secret_access_key to aws.json.'.format(aws_credentials_path))
68  sys.exit(1)
69 
70  try:
71  aws_access_key_id = aws_credentials['aws_access_key_id']
72  aws_secret_access_key = aws_credentials['aws_secret_access_key']
73  except KeyError:
74  print('Invalid config file')
75  raise
76 
77  self.rekognition = boto3.client(
78  'rekognition',
79  aws_access_key_id=aws_access_key_id,
80  aws_secret_access_key=aws_secret_access_key,
81  region_name=region_name)
82 
83  self.dynamodb = boto3.resource(
84  'dynamodb',
85  aws_access_key_id=aws_access_key_id,
86  aws_secret_access_key=aws_secret_access_key,
87  region_name=region_name)
88  self.dynamodb_table = self.dynamodb.Table(self.DYNAMODB_TABLE)
89 
90  self.always_publish = rospy.get_param('~always_publish', True)
91  rospy.loginfo("Publish even if face is not found : {}".format(self.always_publish))
92 
93  self.use_window = rospy.get_param('~use_window', False)
94  rospy.loginfo("Launch image window : {}".format(self.use_window))
95 
96  self.bridge = CvBridge()
97  self.transport_hint = rospy.get_param('~image_transport', 'compressed')
98  rospy.loginfo("Using transport {}".format(self.transport_hint))
99 
100  self.classifier_name = rospy.get_param(
101  "~classifier_name", rospy.get_name())
104  for i, name in enumerate(self.target_names):
105  self.target_name_to_label_index[name] = i
106 
107  self.name_pub = self.advertise('face_name', FaceArrayStamped, queue_size=1)
108  self.pub_rects = self.advertise("~output/rects", RectArray,
109  queue_size=1)
110  self.pub_class = self.advertise("~output/class", ClassificationResult,
111  queue_size=1)
112  if self.transport_hint == 'compressed':
113  self.orig_image_pub = self.advertise('~image/compressed', CompressedImage, queue_size=1)
114  else:
115  self.orig_image_pub = self.advertise('~image', Image, queue_size=1)
116  #
117  # To process latest message, we need to set buff_size must be large enough.
118  # we need to set buff_size larger than message size to use latest message for callback
119  # 640*480(image size) / 5 (expected compressed rate) *
120  # 70 (number of message need to be drop 70 x 30msec = 2100msec processing time)
121  #
122  # c.f. https://answers.ros.org/question/220502/image-subscriber-lag-despite-queue-1/
123  #
124  self.buff_size = rospy.get_param('~buff_size', 640 * 480 * 3 // 5 * 70)
125  rospy.loginfo("rospy.Subscriber buffer size : {}".format(self.buff_size))
126 
127  def subscribe(self):
128  if self.transport_hint == 'compressed':
129  self.image_sub = message_filters.Subscriber('{}/compressed'.format(rospy.resolve_name('image')), CompressedImage, buff_size=self.buff_size)
130  else:
131  self.image_sub = message_filters.Subscriber('image', Image, buff_size=self.buff_size)
132  self.roi_sub = message_filters.Subscriber('face_roi', FaceArrayStamped)
133  self.subs = [self.image_sub, self.roi_sub]
134  queue_size = rospy.get_param('~queue_size', 1)
135  approximate_sync = rospy.get_param('~approximate_sync', True)
136  if approximate_sync:
137  slop = rospy.get_param('~slop', 1.0)
138  self.ts = message_filters.ApproximateTimeSynchronizer(
139  self.subs,
140  queue_size, slop, allow_headerless=True)
141  else:
143  fs=self.subs, queue_size=queue_size)
144  self.ts.registerCallback(self.callback)
145  rospy.loginfo("To process latest incomming message, use approximate_sync with queue_size == 1 is recommended")
146  rospy.loginfo(" approximate_sync : {}".format(approximate_sync))
147  rospy.loginfo(" queue_size : {}".format(queue_size))
148  rospy.loginfo("Waiting for {} and {}".format(self.image_sub.name, self.roi_sub.name))
149 
150  def unsubscribe(self):
151  for sub in self.subs:
152  sub.unregister()
153 
154  def get_label_names(self):
155  items = self.dynamodb_table.scan()['Items']
156  return list(set([item["Name"] for item in items]))
157 
158  def findface(self, face_image):
159  area = face_image.shape[0] * face_image.shape[1]
160  if area < self.FACE_AREA_THRESHOLD / 10:
161  return None
162  if area > self.FACE_AREA_THRESHOLD * 2:
163  # resize
164  ratio = math.sqrt(area / (self.FACE_AREA_THRESHOLD * 2))
165  face_image = cv2.resize(face_image, (int(
166  face_image.shape[1] / ratio), int(face_image.shape[0] / ratio)))
167 
168  _, encoded_face_image = cv2.imencode('.jpg', face_image)
169 
170  # Call API
171  try:
172  res = self.rekognition.search_faces_by_image(
173  CollectionId=self.COLLECTION_ID, Image={'Bytes': encoded_face_image.tobytes()},
174  FaceMatchThreshold=self.FACE_SIMILARITY_THRESHOLD, MaxFaces=self.MAX_FACES)
175  return res
176  except self.rekognition.exceptions.InvalidParameterException as e:
177  rospy.logdebug("No faces detected")
178  except Exception as e:
179  rospy.logerr(e)
180 
181  return None
182 
183  def callback(self, image, roi):
184  start_time = rospy.Time.now()
185  if self.transport_hint == 'compressed':
186  # decode compressed image
187  np_arr = np.fromstring(image.data, np.uint8)
188  img = cv2.imdecode(np_arr, cv2.IMREAD_COLOR)
189  if image.format.find("compressed rgb") > -1:
190  img = img[:, :, ::-1]
191  else:
192  img = self.bridge.imgmsg_to_cv2(image, desired_encoding='bgr8')
193 
194  if self.use_window:
195  img_gray = cv2.cvtColor(img, cv2.COLOR_BGR2GRAY)
196  img_gray = cv2.cvtColor(img_gray, cv2.COLOR_GRAY2BGR)
197 
198  faces = FaceArrayStamped()
199  faces.header = image.header
200  faces.faces = []
201  for face in roi.faces:
202  try:
203  cx = int(face.face.x)
204  cy = int(face.face.y)
205  w = int(face.face.width)
206  h = int(face.face.height)
207  except Exception as e:
208  rospy.logerr(e)
209  return
210 
211  image_roi_slice = np.index_exp[cy - h // 2:cy + h // 2,
212  cx - w // 2:cx + w // 2]
213  ret = self.findface(img[image_roi_slice])
214  if ret != None:
215  if ret['FaceMatches'] != []:
216  try:
217  item = self.dynamodb_table.get_item(
218  Key={'RekognitionId':
219  ret['FaceMatches'][0]['Face']['FaceId']})
220  if not 'Item' in item:
221  rospy.loginfo("Item does not have FaceId {}".format(item))
222  continue
223  face_id = item['Item']['Name']
224  rospy.logdebug("FaceId: {}\n Similarity: {}".format(face_id, \
225  ret['FaceMatches'][0]['Similarity']))
226  faces.faces.append(Face(face=Rect(cx - w // 2, cy - h // 2, w, h),
227  label=face_id,
228  confidence=ret['FaceMatches'][0]['Similarity'] / 100.0))
229  except KeyError as e:
230  rospy.logwarn(
231  "{}: Dynamodb does not have FaceID: {}".format(
232  e, ret['FaceMatches'][0]['Face']['FaceID']))
233 
234  if self.use_window: # copy colored face rectangle to img_gray
235  img_gray[image_roi_slice] = img[image_roi_slice]
236 
237  # is always_publish is False, publish results only when the face is not detected
238  if not self.always_publish and len(faces.faces) <= 0:
239  return
240 
241  self.name_pub.publish(faces)
242 
243  cls_msg = ClassificationResult(
244  header=image.header,
245  classifier=self.classifier_name,
246  target_names=self.target_names,
247  labels=[self.target_name_to_label_index[face.label]
248  for face in faces.faces],
249  label_names=[face.label for face in faces.faces],
250  label_proba=[face.confidence for face in faces.faces],
251  )
252 
253  rects_msg = RectArray(header=image.header)
254  for face in faces.faces:
255  rects_msg.rects.append(face.face)
256  self.pub_rects.publish(rects_msg)
257  self.pub_class.publish(cls_msg)
258 
259  if self.orig_image_pub.get_num_connections() > 0:
260  self.orig_image_pub.publish(image)
261 
262  if self.use_window:
263  cv2.imshow(image._connection_header['topic'], img_gray)
264  cv2.waitKey(1)
265 
266  rospy.loginfo("processing time {} on message taken at {} sec ago".format(
267  (rospy.Time.now() - start_time).to_sec(),
268  (rospy.Time.now() - image.header.stamp).to_sec()))
269 
270 
271 if __name__ == '__main__':
272  rospy.init_node('aws_auto_checkin_service')
273  auto = AutoCheckIn()
274  rospy.spin()
275 
node_scripts.aws_auto_checkin_app.AutoCheckIn.subscribe
def subscribe(self)
Definition: aws_auto_checkin_app.py:127
ssd_train_dataset.int
int
Definition: ssd_train_dataset.py:175
node_scripts.aws_auto_checkin_app.AutoCheckIn.always_publish
always_publish
Definition: aws_auto_checkin_app.py:90
node_scripts.aws_auto_checkin_app.AutoCheckIn.classifier_name
classifier_name
Definition: aws_auto_checkin_app.py:100
node_scripts.aws_auto_checkin_app.AutoCheckIn.target_names
target_names
Definition: aws_auto_checkin_app.py:102
node_scripts.aws_auto_checkin_app.AutoCheckIn
Definition: aws_auto_checkin_app.py:36
node_scripts.aws_auto_checkin_app.AutoCheckIn.target_name_to_label_index
target_name_to_label_index
Definition: aws_auto_checkin_app.py:103
node_scripts.aws_auto_checkin_app.AutoCheckIn.name_pub
name_pub
Definition: aws_auto_checkin_app.py:107
node_scripts.aws_auto_checkin_app.AutoCheckIn.COLLECTION_ID
COLLECTION_ID
Definition: aws_auto_checkin_app.py:53
node_scripts.aws_auto_checkin_app.AutoCheckIn.FACE_AREA_THRESHOLD
FACE_AREA_THRESHOLD
Definition: aws_auto_checkin_app.py:51
node_scripts.aws_auto_checkin_app.AutoCheckIn.rekognition
rekognition
Definition: aws_auto_checkin_app.py:77
message_filters::Subscriber
node_scripts.aws_auto_checkin_app.AutoCheckIn.use_window
use_window
Definition: aws_auto_checkin_app.py:93
node_scripts.aws_auto_checkin_app.AutoCheckIn.callback
def callback(self, image, roi)
Definition: aws_auto_checkin_app.py:183
node_scripts.aws_auto_checkin_app.AutoCheckIn.pub_class
pub_class
Definition: aws_auto_checkin_app.py:110
node_scripts.aws_auto_checkin_app.AutoCheckIn.unsubscribe
def unsubscribe(self)
Definition: aws_auto_checkin_app.py:150
node_scripts.aws_auto_checkin_app.AutoCheckIn.findface
def findface(self, face_image)
Definition: aws_auto_checkin_app.py:158
node_scripts.aws_auto_checkin_app.AutoCheckIn.orig_image_pub
orig_image_pub
Definition: aws_auto_checkin_app.py:113
node_scripts.aws_auto_checkin_app.AutoCheckIn.MAX_FACES
MAX_FACES
Definition: aws_auto_checkin_app.py:55
node_scripts.aws_auto_checkin_app.AutoCheckIn.__init__
def __init__(self)
Definition: aws_auto_checkin_app.py:38
node_scripts.aws_auto_checkin_app.AutoCheckIn.dynamodb_table
dynamodb_table
Definition: aws_auto_checkin_app.py:88
node_scripts.aws_auto_checkin_app.AutoCheckIn.dynamodb
dynamodb
Definition: aws_auto_checkin_app.py:83
node_scripts.aws_auto_checkin_app.AutoCheckIn.transport_hint
transport_hint
Definition: aws_auto_checkin_app.py:97
node_scripts.aws_auto_checkin_app.AutoCheckIn.ts
ts
Definition: aws_auto_checkin_app.py:138
node_scripts.aws_auto_checkin_app.AutoCheckIn.bridge
bridge
Definition: aws_auto_checkin_app.py:96
node_scripts.aws_auto_checkin_app.AutoCheckIn.buff_size
buff_size
Definition: aws_auto_checkin_app.py:124
node_scripts.aws_auto_checkin_app.AutoCheckIn.FACE_SIMILARITY_THRESHOLD
FACE_SIMILARITY_THRESHOLD
Definition: aws_auto_checkin_app.py:52
node_scripts.aws_auto_checkin_app.AutoCheckIn.DYNAMODB_TABLE
DYNAMODB_TABLE
Definition: aws_auto_checkin_app.py:54
message_filters::TimeSynchronizer
node_scripts.aws_auto_checkin_app.AutoCheckIn.pub_rects
pub_rects
Definition: aws_auto_checkin_app.py:108
node_scripts.aws_auto_checkin_app.AutoCheckIn.subs
subs
Definition: aws_auto_checkin_app.py:133
node_scripts.aws_auto_checkin_app.AutoCheckIn.image_sub
image_sub
Definition: aws_auto_checkin_app.py:129
node_scripts.aws_auto_checkin_app.AutoCheckIn.get_label_names
def get_label_names(self)
Definition: aws_auto_checkin_app.py:154
node_scripts.aws_auto_checkin_app.AutoCheckIn.roi_sub
roi_sub
Definition: aws_auto_checkin_app.py:132


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Fri May 16 2025 03:11:16