auto_selector.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 import face_contour_detector.image_information.sql_database as sql_database
00006 import k_nearest_neighbour
00007 from face_contour_detector.srv import *
00008 from face_contour_detector.msg import *
00009 import face_contour_detector.image_information.image_information as image_information
00010 import face_contour_detector.image_information.face_areas as face_areas
00011 import cv_bridge
00012 import cv
00013 import face_contour_detector.gui.image_settings_frame as image_settings_frame
00014 from portrait_robot_msgs.srv import *
00015 
00016 ## @package face_contour_detector.learing.auto_selector
00017 #  This file contains the AutoSelector class which can be used to create filter setting proposals form a knowledge-base.
00018 #  When this file is executed as main script it initializes a rosservice called "experience_autoselector". See service file srv/experience_request.srv
00019 #  @author Fabian Wenzelmann
00020 
00021 ## @brief This class is used to generate proposals for filter settings.
00022 #  @author Fabian Wenzelmann
00023 #
00024 #  A  face_contour_detector.image_information.sql_database.SQLImageDatabase is used to store information about some images. From this values proposals are calculated using the users raiting.
00025 class AutoSelector:
00026         ## @brief constructor method
00027         #  @param self the object pointe
00028         #  @param bridge a cv_bridge. If you already have a bridge this bridge will be used here. Otherwise a new cv_bridge is created
00029     def __init__(self, bridge=None):
00030                 self.images = []
00031                 if bridge is None:
00032                         bridge = cv_bridge.CvBridge()
00033                 self.bridge = bridge
00034         
00035     # field documentation
00036     
00037     ## @var images
00038     #a list of images - type is similar to the return value of face_contour_detector.image_information.sql_database.SQLImageDatabase.get_images()
00039     
00040     ## @var bridge
00041     #  cv_bridge used to convert images
00042     
00043     ## @brief Load the image information database form it's default path.
00044     #  @brief self the object pointer
00045     #
00046     #  Try to load the database from its default path. The <code>images</code> field is set to the value returned by face_contour_detector.image_information.sql_database.SQLImageDatabase.get_images().
00047     #  If opening the database fails images is set to an empty list.
00048     def load_file(self):
00049         sql_db = sql_database.SQLImageDatabase(bridge=self.bridge)
00050         try:
00051             sql_db.load_file()
00052             self.images = sql_db.get_images()
00053         except:
00054             self.images = []
00055         msg_srv = rospy.ServiceProxy("/alubsc/status_msg", alubsc_status_msg)
00056         try:
00057             msg_srv(2, ("opened database containing information about " + str(len(self.images)) + " face images").encode("ascii"))
00058         except:
00059             pass
00060       
00061     ## @brief Choose the parameters where self.images is used as information database.
00062     #  @param self the object pointer
00063     #  @param img sensor_msgs/Image the image to choose the parameter for. The image must be an colored face image (RGB) where all pixels that are not on the mask are set to white.
00064     #  @param mask sensor_msgs/Image the mask to calculate the face areas from.
00065     #
00066     #  The database stores the average brightness of images and the standard deviation of the brightness. We assume that these values correlate with the filter settings. We think that these values are the most important for the parameter settings.
00067     #  We first just find images in the database that are "similar" to img. Brightness and standard deviation of the brightness are used as distance measure.
00068     #  We have a fixed set of possible value combinations (returned by the function face_contour_detector.learing.auto_selector._get_parameter_combinations()). Now we find for each of the face areas the best under those combinations.
00069     #  To do this we check all combinations for this area: Now we find under the similar images those that have "similar" filter settings for this area, according to the curren combination. We then calculate the average raiting of that images. After everything is done we choose the combination with the best average raiting.
00070     #  This image gives an overview:
00071     #  @image html auto_selector.png
00072     #  If the database is empty an exception is thrown.
00073     def choose_parameters(self, img, mask):
00074         cv_img = self.bridge.imgmsg_to_cv(img)
00075         cv_mask = self.bridge.imgmsg_to_cv(mask, "mono8")
00076         extractor = image_information.InformationExtractor()
00077         extractor.information_extractors = [ image_information.AverageValueExtractor() ]
00078         information = extractor.to_dict(cv_img)
00079         new_img = {}
00080         new_img["AveragePixelBrightness"], new_img["StandardBrightnessDeviation"] = information["AveragePixelBrightness"][0], information["StandardBrightnessDeviation"][0]
00081         
00082         # now calculate the 10 most similar images
00083         similar_images = k_nearest_neighbour.k_nearest_neighbours(new_img, self.images, 20, key=self._entry_key_func, key2=self._entry_key_func)
00084         combinations = _get_parameter_combinations()
00085         # now for each area calculate it's parameters
00086         area_resp = face_areas.find_areas(self.bridge.imgmsg_to_cv(mask, "mono8"))
00087         new_areas = [ area_resp.left_eye, area_resp.right_eye, area_resp.nose, area_resp.mouth, area_resp.complete_face ]
00088         selected_areas = []
00089         for area in new_areas:
00090             area_best_raiting = None
00091             best_combination = None
00092             for combination in combinations:
00093                 # for this area find under the similar images those that are near to this image occording the current combination
00094                 parameter_similar = k_nearest_neighbour.k_nearest_neighbours(combination, similar_images, 10, key=lambda params : self._parameter_key(params), key2=self._img_parameter_key(area.name))
00095                 # calculate average raiting
00096                 raiting_sum = 0
00097                 for best_image in parameter_similar:
00098                     raiting_sum += best_image["Raiting"]
00099                 average_raiting = float(raiting_sum) / len(parameter_similar)
00100                 if area_best_raiting is None:
00101                     area_best_raiting = average_raiting
00102                     best_combination = combination
00103                 elif average_raiting < area_best_raiting:
00104                     area_best_raiting = average_raiting
00105                     best_combination = combination
00106             blur_width_pair = name_value_pair("blurwidth".encode("ascii"), str( best_combination["blurwidth"]).encode("ascii"), "int".encode("ascii"))
00107             blur_height_pair = name_value_pair("blurheight".encode("ascii"), str( best_combination["blurheight"] ).encode("ascii"), "int".encode("ascii"))
00108             
00109             threshold1_pair = name_value_pair( "threshold1".encode("ascii"), str(best_combination["threshold1"]).encode("ascii"), "float".encode("ascii"))
00110             threshold2_pair = name_value_pair("threshold2".encode("ascii"), str(best_combination["threshold2"]).encode("ascii"), "float".encode("ascii"))
00111             l2gradientent_pair = name_value_pair("l2gradientent".encode("ascii"), "true".encode("ascii"), "bool".encode("ascii"))
00112             
00113             blur_setup = filter_setup("GaussianBlur".encode("ascii"), [blur_width_pair, blur_height_pair])
00114             canny_setup = filter_setup("Canny".encode("ascii"), [threshold1_pair, threshold2_pair, l2gradientent_pair])
00115             
00116             min_length_pair = name_value_pair("searchRadius".encode("ascii"), "5".encode("ascii"), "int".encode("ascii"))
00117             edge_setup = filter_setup("EdgeConnector".encode("ascii"), [min_length_pair])
00118             
00119             min_num_pair = name_value_pair("minNumPixels".encode("ascii"), "7".encode("ascii"), "int".encode("ascii"))
00120             delete_setup = filter_setup("DeleteShortLines".encode("ascii"), [min_num_pair])
00121             
00122             filters = [blur_setup, canny_setup, edge_setup, delete_setup]
00123             
00124             fa_setup = filter_area_setup(area, filters)
00125             
00126             selected_areas.append(fa_setup)
00127             area_order = ["Complete Face", "Nose", "LeftEye", "RightEye", "Mouth"]
00128             area_sorted = [None, None, None, None, None]
00129             for area in selected_areas:
00130                 if area.area.name == "Complete Face":
00131                     area_sorted[0] = area
00132                 elif area.area.name == "Nose":
00133                     area_sorted[1] = area
00134                 elif area.area.name == "LeftEye":
00135                     area_sorted[2] = area
00136                 elif area.area.name == "RightEye":
00137                     area_sorted[3] = area
00138                 else:
00139                     area_sorted[4] = area
00140             
00141         return autoselect_result(img, area_sorted)
00142     
00143     ## @brief Internal method that is not really important to understand
00144     def _img_parameter_key(self, area_name):
00145         return lambda img : self._parameter_key(img["Areas"][area_name])
00146     
00147     ## @brief Internal method that is not really important to understand
00148     def _parameter_key(self, params):
00149         blur_width = normalize(params["blurwidth"], image_settings_frame.BLUR_WIDTH_MIN, image_settings_frame.BLUR_WIDTH_MAX, 0, 1)
00150         blur_height = normalize(params["blurheight"], image_settings_frame.BLUR_HEIGHT_MIN, image_settings_frame.BLUR_HEIGHT_MAX, 0, 1)
00151         threshold1 = normalize(params["threshold1"], image_settings_frame.CANNY_THRESHOLD1_MIN, image_settings_frame.CANNY_THRESHOLD1_MAX, 0, 1)
00152         threshold2 = normalize(params["threshold1"], image_settings_frame.CANNY_THRESHOLD2_MIN, image_settings_frame.CANNY_THRESHOLD2_MAX, 0, 1)
00153         return blur_width, blur_height, threshold1, threshold2            
00154     
00155     ## @brief Internal method that is not really important to understand 
00156     def _entry_key_func(self, entry):
00157         return normalize(entry["AveragePixelBrightness"], 0.0, 255.0, 0.0, 1.0), normalize(entry["StandardBrightnessDeviation"], 0.0, 127.5, 0.0, 1.0)
00158         
00159 ## @brief Normalize a value, that is in the finite domain between \f$min_{value}\f$ and \f$max_{value}\f$, to a new value between \f$norm_{min}\f$ and \f$norm_{max}\f$
00160 #  @param value the value to normalize
00161 #  @param min_value minimal value of the old domain
00162 #  @param max_value maximal value of the old domain
00163 #  @param norm_min minimal value of the new domain
00164 #  @param norm_max maximal value of the new domain
00165 def normalize(value, min_value, max_value, norm_min, norm_max):
00166     return (value - min_value) * ( (norm_max - norm_min) / (max_value - min_value) ) + norm_min
00167 
00168 ## @brief Returns a finite set of parameter combinations that can be used as filter settings for an image area.   
00169 def _get_parameter_combinations():
00170     blur_width_params = [15, 16, 18, 21, 23]
00171     blur_height_params = [15, 16, 18, 21, 23]
00172     threshold1_params = [2500, 3500, 5500, 7500, 8500, 10000, 15000, 20000]
00173     threshold2_params = [2500, 3500, 5500, 7500, 8500, 10000, 15000, 20000]
00174     
00175     combinations = []
00176     
00177     for blur_width in blur_width_params:
00178         for blur_height in blur_height_params:
00179             for threshold1 in threshold1_params:
00180                 for threshold2 in threshold2_params:
00181                     combinations.append( { "blurwidth" : blur_width, "blurheight" : blur_height, "threshold1" : threshold1, "threshold2" : threshold2 } )
00182     return combinations
00183 
00184 ## @brief Handler for service requests
00185 #  @param req the request, see experience_request
00186 def auto_select_handler(req):
00187     try:
00188         selector = AutoSelector()
00189         selector.load_file()
00190         return experience_requestResponse([selector.choose_parameters(req.image, req.mask)])
00191     except Exception as e:
00192         print(e)
00193         return experience_requestResponse([])
00194 
00195 ## @brief Init a service node with name experience_autoselector and type experience_request
00196 def init_service():
00197     rospy.init_node("face_contour_detector_auto_selector_server")
00198     s1 = rospy.Service("experience_autoselector", experience_request, auto_select_handler)
00199     rospy.spin()
00200     
00201 if __name__ == "__main__":
00202     init_service()
 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