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 """
00009 import roslib
00010 roslib.load_manifest('opencv_tests')
00011 
00012 import sys
00013 import os
00014 from optparse import OptionParser
00015 
00016 import rospy
00017 import sensor_msgs.msg
00018 from cv_bridge import CvBridge
00019 import cv
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     pkgdir = roslib.packages.get_pkg_dir("opencv2")
00038     haarfile = os.path.join(pkgdir, "opencv/share/opencv/haarcascades/haarcascade_frontalface_alt.xml")
00039 
00040     parser = OptionParser(usage = "usage: %prog [options] [filename|camera_index]")
00041     parser.add_option("-c", "--cascade", action="store", dest="cascade", type="str", help="Haar cascade file, default %default", default = haarfile)
00042     (options, args) = parser.parse_args()
00043 
00044     cascade = cv.Load(options.cascade)
00045     br = CvBridge()
00046 
00047     def detect_and_draw(imgmsg):
00048         img = br.imgmsg_to_cv(imgmsg, "bgr8")
00049         # allocate temporary images
00050         gray = cv.CreateImage((img.width,img.height), 8, 1)
00051         small_img = cv.CreateImage((cv.Round(img.width / image_scale),
00052                        cv.Round (img.height / image_scale)), 8, 1)
00053 
00054         # convert color input image to grayscale
00055         cv.CvtColor(img, gray, cv.CV_BGR2GRAY)
00056 
00057         # scale input image for faster processing
00058         cv.Resize(gray, small_img, cv.CV_INTER_LINEAR)
00059 
00060         cv.EqualizeHist(small_img, small_img)
00061 
00062         if(cascade):
00063             faces = cv.HaarDetectObjects(small_img, cascade, cv.CreateMemStorage(0),
00064                                          haar_scale, min_neighbors, haar_flags, min_size)
00065             if faces:
00066                 for ((x, y, w, h), n) in faces:
00067                     # the input to cv.HaarDetectObjects 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                     cv.Rectangle(img, pt1, pt2, cv.RGB(255, 0, 0), 3, 8, 0)
00072 
00073         cv.ShowImage("result", img)
00074         cv.WaitKey(6)
00075 
00076     rospy.init_node('rosfacedetect')
00077     image_topic = rospy.resolve_name("image")
00078     rospy.Subscriber(image_topic, sensor_msgs.msg.Image, detect_and_draw)
00079     rospy.spin()


opencv_tests
Author(s): James Bowman
autogenerated on Sat Dec 28 2013 17:53:20