aws_detect_faces.py

What is this?

../../_images/aws_detect_faces.png

Detect faces within an images using Amazon Rekognition. Please refer to DetectFaces.

Subscribing Topic

  • image/compressed (sensor_msgs/CompressedImage)

    Input image. This topic name is resolved from image.

Publishing Topic

  • ~faces (opencv_apps/FaceArrayStamped)

    Detected face positions, facial landmarks, emotions, presence of beard, sunglasses, and so on.

  • ~poses (geometry_msgs/PoseArray)

    Pose of the face as determined by its pitch, roll, and yaw. The pose is published in Quaternion, to reconstruct Roll, Pitch, Yaw, use following codes.

import math
import rospy
from geometry_msgs.msg import PoseArray

from tf.transformations import euler_from_quaternion

def cb(msg):
    for pose in msg.poses:
        angles = euler_from_quaternion([pose.orientation.x, pose.orientation.y, pose.orientation.z, pose.orientation.w])
        print("roll: {}, pitch: {}, yaw: {}".format(angles[0]*180/math.pi,angles[1]*180/math.pi,angles[2]*180/math.pi))

if __name__ == '__main__':
    rospy.init_node('pose_example')
    rospy.Subscriber('/aws_detect_faces/poses', PoseArray, cb)
    rospy.spin()
  • ~attributes (jsk_recognition_msgs/ClassificationResult)

    Attributes of the face, such as emotions, presence of beard, sunglasses, and so on, with confidence.

  • ~landmarks (jsk_recognition_msgs/PeoplePoseArray)

    The location of landmarks on the face.

  • ~output (sensor_msgs/Image)

    Visualization image of detected faces.

Parameters

{
    "region" : "xxxxxxxxxxxxxxxxxxxx",
    "aws_access_key_id" : "####################",
    "aws_secret_access_key" : "********************"
}

Example

roslaunch jsk_perception sample_aws_detect_faces.launch

Optional Arguments:
  attributes (default "ALL"): set either ALL or DEFAULT for returning attributes
  use_usb_cam (default "false"): set true to use USB camera image as input
  use_window (default "true"): set false if you do not want to display window

For JSK user, Download aws.json file from Gdrive and put this under /tmp directory to run sample code.