rosfacedetect.py
Go to the documentation of this file.
00001 #!/usr/bin/python
00002 """
00003 This program is demonstration for face and object detection using haar-like features.
00004 The program finds faces in a camera image or video stream and displays a red box around them.
00005 
00006 Original C implementation by:  ?
00007 Python implementation by: Roman Stanchak, James Bowman
00008 Updated: Copyright (c) 2016, Tal Regev.
00009 """
00010 
00011 import sys
00012 import os
00013 from optparse import OptionParser
00014 
00015 import rospy
00016 import sensor_msgs.msg
00017 from cv_bridge import CvBridge
00018 import cv2
00019 import numpy
00020 
00021 # Parameters for haar detection
00022 # From the API:
00023 # The default parameters (scale_factor=2, min_neighbors=3, flags=0) are tuned
00024 # for accurate yet slow object detection. For a faster operation on real video
00025 # images the settings are:
00026 # scale_factor=1.2, min_neighbors=2, flags=CV_HAAR_DO_CANNY_PRUNING,
00027 # min_size=<minimum possible face size
00028 
00029 min_size      = (10, 10)
00030 image_scale   = 2
00031 haar_scale    = 1.2
00032 min_neighbors = 2
00033 haar_flags    = 0
00034 
00035 if __name__ == '__main__':
00036 
00037     # TODO add this file in the repository and make it relative to this python script. (not all people will run this from linux)
00038     haarfile = '/usr/share/opencv/haarcascades/haarcascade_frontalface_alt.xml'
00039 
00040     parser = OptionParser(usage = "usage: %prog [options]")
00041     parser.add_option("-c", "--cascade", action="store", dest="cascade", type="str", help="Haar cascade file, default %default", default = haarfile)
00042     parser.add_option("-t", "--topic", action="store", dest="topic", type="str", help="Topic to find a face on, default %default", default = '/camera/rgb/image_raw')
00043     parser.add_option("-ct", "--ctopic", action="store", dest="ctopic", type="str", help="Compressed topic to find a face on, default %default", default = '/camera/rgb/image/compressed')
00044     (options, args) = parser.parse_args()
00045 
00046     cascade = cv2.CascadeClassifier()
00047     cascade.load(options.cascade)
00048     br = CvBridge()
00049 
00050     def detect_and_draw(imgmsg):
00051         img = br.imgmsg_to_cv2(imgmsg, "bgr8")
00052         # allocate temporary images
00053         new_size = (int(img.shape[1] / image_scale), int(img.shape[0] / image_scale))
00054 
00055         # convert color input image to grayscale
00056         gray = cv2.cvtColor(img, cv2.COLOR_BGR2GRAY)
00057 
00058         # scale input image for faster processing
00059         small_img = cv2.resize(gray, new_size, interpolation = cv2.INTER_LINEAR)
00060 
00061         small_img = cv2.equalizeHist(small_img)
00062 
00063         if(cascade):
00064             faces = cascade.detectMultiScale(small_img, haar_scale, min_neighbors, haar_flags, min_size)
00065             if faces is not None:
00066                 for (x, y, w, h) in faces:
00067                     # the input to detectMultiScale was resized, so scale the
00068                     # bounding box of each face and convert it to two CvPoints
00069                     pt1 = (int(x * image_scale), int(y * image_scale))
00070                     pt2 = (int((x + w) * image_scale), int((y + h) * image_scale))
00071                     cv2.rectangle(img, pt1, pt2, (255, 0, 0), 3, 8, 0)
00072 
00073         cv2.imshow("result", img)
00074         cv2.waitKey(6)
00075 
00076     def compressed_detect_and_draw(compressed_imgmsg):
00077         img = br.compressed_imgmsg_to_cv2(compressed_imgmsg, "bgr8")
00078         # allocate temporary images
00079         new_size = (int(img.shape[1] / image_scale), int(img.shape[0] / image_scale))
00080 
00081         # convert color input image to grayscale
00082         gray = cv2.cvtColor(img, cv2.COLOR_BGR2GRAY)
00083 
00084         # scale input image for faster processing
00085         small_img = cv2.resize(gray, new_size, interpolation = cv2.INTER_LINEAR)
00086 
00087         small_img = cv2.equalizeHist(small_img)
00088 
00089         if(cascade):
00090             faces = cascade.detectMultiScale(small_img, haar_scale, min_neighbors, haar_flags, min_size)
00091             if faces is not None:
00092                 for (x, y, w, h) in faces:
00093                     # the input to detectMultiScale was resized, so scale the
00094                     # bounding box of each face and convert it to two CvPoints
00095                     pt1 = (int(x * image_scale), int(y * image_scale))
00096                     pt2 = (int((x + w) * image_scale), int((y + h) * image_scale))
00097                     cv2.rectangle(img, pt1, pt2, (255, 0, 0), 3, 8, 0)
00098 
00099         cv2.imshow("compressed_result", img)
00100         cv2.waitKey(6)
00101 
00102     rospy.init_node('rosfacedetect')
00103     rospy.Subscriber(options.topic, sensor_msgs.msg.Image, detect_and_draw)
00104     rospy.Subscriber(options.ctopic, sensor_msgs.msg.CompressedImage, compressed_detect_and_draw)
00105     rospy.spin()


opencv_tests
Author(s): James Bowman
autogenerated on Thu Jun 6 2019 21:23:40