12 from __future__
import division
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
26 from cv_bridge
import CvBridge
33 from jsk_topic_tools
import ConnectionBasedTransport
41 env_path = rospy.get_param(
'~env_path',
'env.json')
42 rospy.loginfo(
"Loading AutoCheckin env variables from {}".format(env_path))
44 with open(env_path)
as env_json:
45 env = json.load(env_json)
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))
56 region_name = env[
'Region']
58 print(
'Invalid config file')
61 aws_credentials_path = rospy.get_param(
'~aws_credentials_path',
'aws.json')
62 rospy.loginfo(
"Loading AWS credentials from {}".format(aws_credentials_path))
64 with open(aws_credentials_path)
as aws_json:
65 aws_credentials = json.load(aws_json)
67 rospy.logerr(
'Cannot open "{}".\n Please put region/aws_access_key_id/aws_secret_access_key to aws.json.'.format(aws_credentials_path))
71 aws_access_key_id = aws_credentials[
'aws_access_key_id']
72 aws_secret_access_key = aws_credentials[
'aws_secret_access_key']
74 print(
'Invalid config file')
79 aws_access_key_id=aws_access_key_id,
80 aws_secret_access_key=aws_secret_access_key,
81 region_name=region_name)
85 aws_access_key_id=aws_access_key_id,
86 aws_secret_access_key=aws_secret_access_key,
87 region_name=region_name)
91 rospy.loginfo(
"Publish even if face is not found : {}".format(self.
always_publish))
94 rospy.loginfo(
"Launch image window : {}".format(self.
use_window))
101 "~classifier_name", rospy.get_name())
107 self.
name_pub = self.advertise(
'face_name', FaceArrayStamped, queue_size=1)
108 self.
pub_rects = self.advertise(
"~output/rects", RectArray,
110 self.
pub_class = self.advertise(
"~output/class", ClassificationResult,
113 self.
orig_image_pub = self.advertise(
'~image/compressed', CompressedImage, queue_size=1)
115 self.
orig_image_pub = self.advertise(
'~image', Image, queue_size=1)
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))
134 queue_size = rospy.get_param(
'~queue_size', 1)
135 approximate_sync = rospy.get_param(
'~approximate_sync',
True)
137 slop = rospy.get_param(
'~slop', 1.0)
138 self.
ts = message_filters.ApproximateTimeSynchronizer(
140 queue_size, slop, allow_headerless=
True)
143 fs=self.
subs, queue_size=queue_size)
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))
151 for sub
in self.
subs:
156 return list(set([item[
"Name"]
for item
in items]))
159 area = face_image.shape[0] * face_image.shape[1]
165 face_image = cv2.resize(face_image, (
int(
166 face_image.shape[1] / ratio),
int(face_image.shape[0] / ratio)))
168 _, encoded_face_image = cv2.imencode(
'.jpg', face_image)
173 CollectionId=self.
COLLECTION_ID, Image={
'Bytes': encoded_face_image.tobytes()},
176 except self.
rekognition.exceptions.InvalidParameterException
as e:
177 rospy.logdebug(
"No faces detected")
178 except Exception
as e:
184 start_time = rospy.Time.now()
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]
192 img = self.
bridge.imgmsg_to_cv2(image, desired_encoding=
'bgr8')
195 img_gray = cv2.cvtColor(img, cv2.COLOR_BGR2GRAY)
196 img_gray = cv2.cvtColor(img_gray, cv2.COLOR_GRAY2BGR)
198 faces = FaceArrayStamped()
199 faces.header = image.header
201 for face
in roi.faces:
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:
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])
215 if ret[
'FaceMatches'] != []:
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))
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),
228 confidence=ret[
'FaceMatches'][0][
'Similarity'] / 100.0))
229 except KeyError
as e:
231 "{}: Dynamodb does not have FaceID: {}".format(
232 e, ret[
'FaceMatches'][0][
'Face'][
'FaceID']))
235 img_gray[image_roi_slice] = img[image_roi_slice]
243 cls_msg = ClassificationResult(
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],
253 rects_msg = RectArray(header=image.header)
254 for face
in faces.faces:
255 rects_msg.rects.append(face.face)
263 cv2.imshow(image._connection_header[
'topic'], img_gray)
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()))
271 if __name__ ==
'__main__':
272 rospy.init_node(
'aws_auto_checkin_service')