face_areas.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 import roslib
00003 roslib.load_manifest('face_contour_detector')
00004 import rospy
00005 from face_contour_detector.srv import *
00006 from face_contour_detector.msg import *
00007 import cv
00008 import cv_bridge
00009 
00010 ## @package face_contour_detector.image_information.face_areas
00011 #  Provides a function to estimate the face area positions. Also inits a rosservice with name "find_face_areas" if this file is run as main script.
00012 #  @author Fabian Wenzelmann
00013 
00014 ## @brief Estimates the area for nose, mouth, left eye, right eye and the complete face.
00015 #  @param mask cvMat of type "mono8". Everything that is black in this image is part of the head.
00016 #  see srv/FindFaceAreas.srv
00017 #  the positions of the areas are only estimated. The image is divided into five parts horizontally and three parts vertically.
00018 #  The face positions are estimated using the following pattern:
00019 #  @image html face_areas.png
00020 def find_areas(mask):
00021     min_left = max_right = min_top = max_bot = None
00022     width, height = mask.width, mask.height
00023     width_range = range( width )
00024     height_range = range( height )
00025     for row in height_range:
00026         if row >= int( 0.8 * height ):
00027             break
00028         for col in width_range:
00029             if mask[row, col] <= 128:
00030                 if min_left is None:
00031                     min_left = col
00032                 if max_right is None:
00033                     max_right = col
00034                 if min_top is None:
00035                     min_top = row
00036                 if max_bot is None:
00037                     max_bot = row
00038                 min_left, max_right = min(min_left, col), max(max_right, col)
00039                 min_top, max_bot = min(min_top, row), max(max_bot, row)
00040     # add some spacing for hairline
00041     face_top = min_top
00042     min_top += int(width * 1/5.5)
00043     face_width, face_height = max_right - min_left, max_bot - min_top
00044     pos_x = lambda face_x: min_left + face_x
00045     pos_y = lambda face_y: min_top + face_y
00046     pos_img = lambda face_x, face_y: (min_left + face_x, min_top + face_y)
00047     fifth, third, sixth = 1/5.0, 1/3.0, 1/6.0
00048     left_eye_x, right_eye_x = int(fifth * face_width), int(3 * fifth * face_width)
00049     eye_top = int(third * face_height)
00050     eye_height = int(sixth * face_height)
00051     eye_width = int(fifth * face_width)
00052     
00053     nose_x = int(2 * fifth * face_width)
00054     nose_y = eye_top + int(eye_height / 6)
00055     nose_height = int(1.75 * fifth * face_height)
00056     nose_width = int(fifth * face_width * 0.75)
00057     
00058     mouth_width = int(1.5 * eye_width)
00059     mouth_x = int((nose_x + (nose_width / 2.0)) - (mouth_width /2.0))
00060     mouth_y = int(nose_x + nose_height + (1/24.0 * face_height))
00061     mouth_height = int((20/173.0) * face_height)
00062     
00063     left_eye_x, right_eye_x, eye_top = pos_x(left_eye_x), pos_x(right_eye_x), pos_y(eye_top)
00064     nose_x, nose_y = pos_x(nose_x), pos_y(nose_y)
00065     mouth_x, mouth_y = pos_x(mouth_x), pos_y(mouth_y)
00066     # not nice but works
00067     x_vals = [left_eye_x, right_eye_x, nose_x, mouth_x]
00068     y_vals = [eye_top, nose_y, mouth_y]
00069     x_vals = map(lambda v: _correct_pos(v, width), x_vals)
00070     y_vals = map(lambda v: _correct_pos(v, height), y_vals)
00071     left_eye_x, right_eye_x, nose_x, mouth_x = x_vals[0], x_vals[1], x_vals[2], x_vals[3]
00072     eye_top, nose_y, mouth_y = y_vals[0], y_vals[1], y_vals[2]
00073     
00074     left_eye = image_area("LeftEye".encode("ascii"), left_eye_x, eye_top, eye_width, eye_height)
00075     right_eye = image_area("RightEye".encode("ascii"), right_eye_x, eye_top, eye_width, eye_height)
00076     nose = image_area("Nose".encode("ascii"), nose_x, nose_y, nose_width, nose_height)
00077     mouth = image_area("Mouth".encode("ascii"), mouth_x, mouth_y, mouth_width, mouth_height)
00078     complete = image_area("Complete Face".encode("ascii"), min_left, face_top, face_width, height - face_top)
00079     return FindFaceAreasResponse(left_eye, right_eye, nose, mouth, complete)
00080     
00081 def _correct_pos(val, max_):
00082     val = max(val, 0)
00083     val = min(val, max_)
00084     return val
00085     
00086 
00087 def get_areas(req):
00088     bridge = cv_bridge.CvBridge()
00089     cv_img = bridge.imgmsg_to_cv(req.mask, "mono8")
00090     return find_areas(cv_img)
00091 
00092 def init_area_node():
00093     rospy.init_node("face_area_server")
00094     s1 = rospy.Service("find_face_areas", FindFaceAreas, get_areas)
00095     rospy.spin()
00096 
00097 if __name__ == "__main__":
00098     init_area_node()
00099     
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends


face_contour_detector
Author(s): Fabian Wenzelmann and Julian Schmid
autogenerated on Wed Dec 26 2012 16:18:17