image_settings_frame.py
Go to the documentation of this file.
00001 # -*- coding: utf-8 -*-
00002 # never read this code - it's ugly
00003 import Tkinter
00004 import roslib
00005 roslib.load_manifest('face_contour_detector')
00006 import rospy
00007 import cv
00008 import cv_bridge
00009 import Image
00010 import ImageTk
00011 import tkMessageBox
00012 from face_contour_detector.srv import *
00013 from face_contour_detector.msg import *
00014 import face_contour_detector.image_information.sql_database as sql_database
00015 
00016 ## @package face_contour_detector.gui.image_settings_frame
00017 #
00018 #  This module defines two classes: JumpScale which is a subclass of Tkinter.Scale but jumps to the position where it is clicked instead of moving a fixed amount.
00019 #  The second class is the ImageSettingsFrame itself. A frame which contains several sliders for all available filters and allows the user to modify them.
00020 #  @author Fabian Wenzelmann
00021 
00022 # todo egtl nen log wenn init stattfindet das er nicht immer neu malt
00023 
00024 ## @brief constant defining the minimum value for blur width
00025 BLUR_WIDTH_MIN = 1
00026 ## @brief constant defining the maximum value for blur width
00027 BLUR_WIDTH_MAX = 50
00028 
00029 ## @brief constant defining the minimum value for blur height
00030 BLUR_HEIGHT_MIN = 1
00031 ## @brief constant defining the maximum value for blur height
00032 BLUR_HEIGHT_MAX = 50
00033 
00034 ## @brief constant defining the minimum value for canny threshold1
00035 CANNY_THRESHOLD1_MIN = 1
00036 ## @brief constant defining the maximum value for canny threshold1
00037 CANNY_THRESHOLD1_MAX = 30000
00038 
00039 ## @brief constant defining the minimum value for canny threshold2
00040 CANNY_THRESHOLD2_MIN = 1
00041 ## @brief constant defining the maximum value for canny threshold2
00042 CANNY_THRESHOLD2_MAX = 30000
00043 
00044 ## @brief constant defining the minimal search radius for edge connection
00045 SEARCH_RADIUS_MIN = 1
00046 ## @brief constant defining the maximum search radius for edge connection
00047 SEARCH_RADIUS_MAX = 20
00048 
00049 ## @brief constant defining the minimal amount of pixels that can be passed as argument to the short line deletion filter
00050 PIXEL_NUM_MIN = 1
00051 ## @brief constant defining the maximal amount of pixels that can be passed as argument to the short line deletion filter
00052 PIXEL_NUM_MAX = 20
00053 
00054 ## @brief The length of all sliders used on this frame
00055 SLIDER_LENGTH = 200
00056 
00057 ## @brief This field saves the original with all filters applied according to the current settings as sensor_msgs/Image. Initially it is set to None.
00058 current_image = None
00059 
00060 ## @brief A class that behaves like the Tkinter Scale widget but if you click on it the slider jumps to the clicked position.
00061 #  @author Fabian Wenzelmann
00062 #
00063 #  This class is made for a narrow purpose! It only works with horizontal sliders and binding an event to this widget with the bind()
00064 #  method does not work anymore.
00065 class JumpScale(Tkinter.Scale):
00066     ## @brief Constroctur method
00067     #  @param self the object pointer
00068     #  @param master Tkinter master widget
00069     #  @param options additional parameters for this sliders as in the Tkinter.Scale widget
00070     def __init__(self, master=None, **options):
00071         Tkinter.Scale.__init__(self, master, options)
00072         dif = self["to"] - self["from"]
00073         self.factor = dif / self["length"]
00074         self.bind("<1>", self._jump)
00075     
00076     # member variable documentation
00077     
00078     ## @var factor
00079     #  the factor that is used to calculate the position when the user clicks on the widget - the factor is defined as \f$ \frac{Scale_{to} - Scale_{from}}{Scale_{length}} \f$ where \f$ Scale_{to}\f$ is the maximum value of the slider, \f$Scale_{from}\f$ the minimum value of the slider and \f$ Scale_{length}\f$ is the length of the slider
00080     
00081     ## @brief Methhod that makes the slider jump to the correct position
00082     #
00083     #  @param self the object pointer
00084     #  @param evt the mouse event that caused the execution of this function
00085     def _jump(self, evt):
00086         x, y = evt.x, evt.y
00087         _id = self.identify(x, y)
00088         if _id == "trough1" or _id == "trough2":
00089             self.set(self.factor * x + self["from"])
00090 
00091 
00092 ## @brief Frame to modify filter parameters.
00093 #  @author Fabian Wenzelmann
00094 #
00095 #  This frame is used to modify the arguments for the filter. Each filter is grouped together with sliders and text fields for all its parameters.
00096 #  The text fields and sliders are linked together so you can modify both. The filters and its parameters are:
00097 #  <ul>
00098 #       <li>
00099 #               Gaussian Blur
00100 #               <ul> <li>Blur width</li><li>Blur height</li> </ul>
00101 #       </li>
00102 #       <li>
00103 #               Canny
00104 #               <ul><li>m_threshold1</li><li>m_threshold2</li></ul>
00105 #               as defined in the opencv documentation
00106 #       </li>
00107 #       <li>
00108 #               Edge Connector
00109 #               <ul><li>Search Radius</li></ul>
00110 #       </li>
00111 #       <li>
00112 #               Delete Short Lines
00113 #               <ul><li>Min length</li></ul>
00114 #       </li>
00115 #  </ul>
00116 #  The resulting image using the current filter settings (as a "preview") is displayed on the right side of the frame.
00117 #  Since each image is seperated in areas (for mouth, eyes and so on) the values of the filters can be set for each of those areas.
00118 #  All areas are accessible through a OptionMenu. The areas can be adjusted by hand to correct the position.
00119 #  The selected area is surrounded by a red rectangle (in the preview). If the mouse moves over the image also a blue rectangle is drawn
00120 #  which marks the new position of this area when the users presses the left mouse key.
00121 #  There is a button "apply" which updates the preview image by applying the filter-settings on the original image. There's also the option "Immediately apply changes".
00122 #  If this value is set to yes (by activating a check button) the preview image is updated each time the user changes one of the filter settings. Hower this can become very slow depending on the image and the current settings...
00123 #  The user presses the "Commit" button to commit the current settings and edge image to the main gui.
00124 #  Below the preview image there is a group of six RadioButtons. The user can rate the image with the current settings. The raitings are saved in a database and are used for our "learning" algorithm (well lets say it tries to do something useful according to the collected data).
00125 #  1 is the worste and 6 is the best raiting.
00126 #  Below there's an example image:
00127 #  @image html image_settings_frame.png
00128 class ImageSettingsFrame(Tkinter.Frame):
00129     ## @brief Constructor method
00130     #  @param self the object pointer
00131     #  @param master the Tkinter master widget (usually a Tkinter.Toplevel)
00132     #  @param filter_settings is of type autoselect_result (message type)
00133     def __init__(self, master, filter_settings):
00134         # call the superclass constructor
00135         Tkinter.Frame.__init__(self, master)
00136         # a cv_bridge used for this frame
00137         self.master.title("Filter Settings")
00138         self.bridge = bridge = cv_bridge.CvBridge()
00139         # keep a reference to the original image
00140         self.original_image = filter_settings.image
00141         # we also need the image as cvMat
00142         self.orignal_image_as_cvM = bridge.imgmsg_to_cv(self.original_image)
00143         # save all areas in a hashmap
00144         self.areas = areas = {}
00145         for area in filter_settings.areas:
00146             areas[area.area.name] = area
00147         # also save the list for the service call
00148         self.list_areas = filter_settings.areas
00149         
00150         # create "subframes"
00151         area_frame = Tkinter.LabelFrame(self, text="Image Area")
00152         self.area_selection = area_selection = Tkinter.StringVar(master=self)
00153         area_selection.set(filter_settings.areas[0].area.name)
00154         area_box = apply(Tkinter.OptionMenu, (area_frame, area_selection) + tuple( [area.area.name for area in filter_settings.areas]))
00155         box_label = Tkinter.Label(area_frame, text="Selected Area: ")
00156         
00157         area_box.grid(row=0, column=1, sticky="W")
00158         box_label.grid(row=0, column=0, sticky="W")
00159         
00160         # filter and settings frame
00161         blur_frame = Tkinter.LabelFrame(self, text="Gaussian Blur")
00162         canny_frame = Tkinter.LabelFrame(self, text="Canny")
00163         connect_frame = Tkinter.LabelFrame(self, text="Connect Edges")
00164         delete_frame = Tkinter.LabelFrame(self, text="Delete Short Lines")
00165         settings_frame = Tkinter.LabelFrame(self, text="Settings / Options")
00166         
00167         # Blur
00168         self.blur_width = blur_width = Tkinter.IntVar(master=self)
00169         self.blur_height = blur_height = Tkinter.IntVar(master=self)
00170         
00171         blur_width_slider = JumpScale(blur_frame, from_=BLUR_WIDTH_MIN, to=BLUR_WIDTH_MAX, orient=Tkinter.HORIZONTAL, label="blur width", variable=blur_width, tickinterval=_slider_tickinterval(BLUR_WIDTH_MIN, BLUR_WIDTH_MAX), length=SLIDER_LENGTH, showvalue=False)
00172         # TODO: validate?
00173         blur_width_txt_field = Tkinter.Entry(blur_frame, textvariable=blur_width, width=len(str(BLUR_WIDTH_MAX)) + 1)
00174         
00175         blur_height_slider = JumpScale(blur_frame, from_=BLUR_HEIGHT_MIN, to=BLUR_HEIGHT_MAX, orient=Tkinter.HORIZONTAL, label="blur height", variable=blur_height, tickinterval=_slider_tickinterval(BLUR_HEIGHT_MIN, BLUR_HEIGHT_MAX), length=SLIDER_LENGTH, showvalue=False)
00176         blur_height_txt_field = Tkinter.Entry(blur_frame, textvariable=blur_height, width=len(str(BLUR_HEIGHT_MAX)) + 1)
00177         
00178         blur_width_slider.grid(row=0, column=0)
00179         blur_width_txt_field.grid(row=1, column=0, sticky="W")
00180         blur_height_slider.grid(row=2, column=0, sticky="WE")
00181         blur_height_txt_field.grid(row=3, column=0, sticky="W")
00182         
00183         self.c_threshold1 = c_threshold1 = Tkinter.IntVar(master=self)
00184         self.c_threshold2 = c_threshold2 = Tkinter.IntVar(master=self)
00185         
00186         # Canny
00187         c_threshold1_slider = JumpScale(canny_frame, from_=CANNY_THRESHOLD1_MIN, to=CANNY_THRESHOLD1_MAX, orient=Tkinter.HORIZONTAL, label="threshold 1", variable=c_threshold1, tickinterval=_slider_tickinterval(CANNY_THRESHOLD1_MIN, CANNY_THRESHOLD1_MAX, 2), length=SLIDER_LENGTH, showvalue=False)
00188         c_threshold1_txt_field = Tkinter.Entry(canny_frame, textvariable=c_threshold1, width=len(str(CANNY_THRESHOLD1_MAX)) + 1)
00189         
00190         c_threshold2_slider = JumpScale(canny_frame, from_=CANNY_THRESHOLD2_MIN, to=CANNY_THRESHOLD2_MAX, orient=Tkinter.HORIZONTAL, label="threshold 2", variable=c_threshold2, tickinterval=_slider_tickinterval(CANNY_THRESHOLD2_MIN, CANNY_THRESHOLD2_MAX, 2), length=SLIDER_LENGTH, showvalue=False)
00191         c_threshold2_txt_field = Tkinter.Entry(canny_frame, textvariable=c_threshold2, width=len(str(CANNY_THRESHOLD2_MAX)) + 1)
00192         
00193         c_threshold1_slider.grid(row=0, column=0)
00194         c_threshold1_txt_field.grid(row=1, column=0, sticky="W")
00195         c_threshold2_slider.grid(row=2, column=0)
00196         c_threshold2_txt_field.grid(row=3, column=0, sticky="W")
00197         
00198         # Edge connector
00199         self.s_radius = s_radius = Tkinter.IntVar(master=self)
00200         s_radius_slider = JumpScale(connect_frame, from_=SEARCH_RADIUS_MIN, to=SEARCH_RADIUS_MAX, orient=Tkinter.HORIZONTAL, label="search radius", variable=s_radius, tickinterval=_slider_tickinterval(SEARCH_RADIUS_MIN, SEARCH_RADIUS_MAX), length=SLIDER_LENGTH, showvalue=False)
00201         s_radius_txt_field = Tkinter.Entry(connect_frame, textvariable=s_radius, width=len(str(SEARCH_RADIUS_MAX)) + 1)
00202         
00203         s_radius_slider.grid(row=0, column=0)
00204         s_radius_txt_field.grid(row=1, column=0, sticky="W")
00205         
00206         # Delete short lines
00207         self.min_length = min_length = Tkinter.IntVar(master=self)
00208         min_length_slider = JumpScale(delete_frame, from_=PIXEL_NUM_MIN, to=PIXEL_NUM_MAX, orient=Tkinter.HORIZONTAL, label="min line length", variable=min_length, tickinterval=_slider_tickinterval(PIXEL_NUM_MIN, PIXEL_NUM_MAX), length=SLIDER_LENGTH, showvalue=False)
00209         min_length_txt_field = Tkinter.Entry(delete_frame, textvariable=min_length, width=len(str(PIXEL_NUM_MAX)) + 1)
00210         
00211         min_length_slider.grid(row=0, column=0)
00212         min_length_txt_field.grid(row=1, column=0, sticky="W")
00213         
00214         # some settings
00215         self.immediately_apply = immediately_apply = Tkinter.IntVar(master=self)
00216         immediately_apply_box = Tkinter.Checkbutton(settings_frame, text="Immediately apply changes", variable=immediately_apply)
00217         apply_button = Tkinter.Button(settings_frame, text="Apply", command=self._apply_and_display)
00218         
00219         commit_button = Tkinter.Button(settings_frame, text="Commit", command=self._commit)
00220         
00221         immediately_apply_box.grid(row=0, column=0)
00222         apply_button.grid(row=1, column=0, sticky="W")
00223         commit_button.grid(row=1, column=1, sticky="W")
00224         
00225         # grid the subframes
00226         blur_frame.grid(row=1, column=0)
00227         canny_frame.grid(row=1, column=1)
00228         connect_frame.grid(row=2, column=0, sticky="WE", padx=10, pady=10)
00229         delete_frame.grid(row=2, column=1, sticky="WE")
00230         settings_frame.grid(row=3, column=0, columnspan=2, pady=10, sticky="WE", padx=10)
00231         area_frame.grid(row=0, column=0, sticky="WE", columnspan=2, padx=10)
00232         
00233         area_selection.trace("w", self._area_selection_callback)
00234         #self._set_parameter_values()
00235         # we also need a frame to display the result image
00236         image_frame = self.image_frame = Tkinter.LabelFrame(self, text="Result Image")
00237         
00238         image_label = self.image_label = Tkinter.Label(self.image_frame)
00239         image_label.bind("<Motion>", self._mouse_motion_callback)
00240         image_label.bind("<1>", self._mouse_click_callback)
00241         self._init_area_values()
00242         self._apply_and_display()
00243         
00244         # we also need radio buttons for the raiting
00245         raiting = self.raiting = Tkinter.IntVar(master=self, value=3)
00246         for i in range(1, 7):
00247             rb = Tkinter.Radiobutton(image_frame, text=str(i), variable=raiting, value=i)
00248             rb.grid(row=1, column=i-1)
00249         image_label.grid(row=0, column=0, columnspan=6)
00250         rate_button = Tkinter.Button(image_frame, text="Rate", relief=Tkinter.SUNKEN, command=self._rate_callback)
00251         rate_button.grid(row=2, column=0, columnspan=6, sticky="WE")
00252         
00253         image_frame.grid(row=0, column=3, rowspan=4, padx=10)
00254         
00255         self._set_display_image(self.as_py_image)
00256         immediately_apply.trace("w", self._area_selection_callback)
00257         
00258         parameter_value_changed = lambda p_name : lambda *args : self._parameter_value_changed(p_name, args)
00259         
00260         blur_width.trace("w", parameter_value_changed("blurwidth"))
00261         blur_height.trace("w", parameter_value_changed("blurheight"))
00262         
00263         c_threshold1.trace("w", parameter_value_changed("threshold1"))
00264         c_threshold2.trace("w", parameter_value_changed("threshold2"))
00265 
00266         s_radius.trace("w", parameter_value_changed("minNumPixels"))
00267         
00268         min_length.trace("w", parameter_value_changed("searchRadius"))
00269         
00270         # create a sql database connection
00271         sql_db = self.sql_db = sql_database.SQLImageDatabase(bridge=self.bridge)
00272         try:
00273             sql_db.load_file()
00274         except:
00275             self.sql_db = None
00276             tkMessageBox.showerror(message="Unable to load / create image information database file. Raiting button will not work!", parent=self, title="Error")
00277     
00278     # Member variable documentation
00279     ## @var bridge
00280     #  a cv_bridge that is used to transform images from sensor_msgs/Image to cvMat and vice versa
00281     
00282     ## @var original_image
00283     #  the original image as passed from the proposals as sensor_msgs/Image
00284     
00285     ## @var orignal_image_as_cvM
00286     #  also save the original image as cvMat - this is required to add information about the image in the database.
00287     
00288     ## @var areas
00289     #  All areas of this image - but packed in a python dictionary to speedup the lookup the filter settings when the currently selected area is used as identifier of the area
00290     
00291     ## @var list_areas
00292     #  All areas of this image - it's list of msg/image_area
00293     
00294     ## @var area_selection
00295     #  A Tkinter.StringVar that stores the name of the selected area
00296     
00297     ## @var blur_width
00298     #  Tkinter variable that stores the blur width parameter value
00299     
00300     ## @var blur_height
00301     #  Tkinter variable that stores the blur height parameter value
00302     
00303     ## @var c_threshold1
00304     #  Tkinter variable that stores the canny threshold1 parameter value
00305     
00306     ## @var c_threshold2
00307     #  Tkinter variable that stores the canny threshold2 parameter value
00308     
00309     ## @var s_radius
00310     #  Tkinter variable that stores the search radius paramter value for the edge connector
00311     
00312     ## @var min_length
00313     #  Tkinter variable that stores the min_length parameter value for delete short lines
00314     
00315     ## @var immediately_apply
00316     #  Tkinter variable that stores if changes of the filter values should always cause the preview image to update
00317     
00318     ## @var image_frame
00319     #  The Tkinter.LabelFrame that contains the preview label and raiting stuff
00320     
00321     ## @var image_label
00322     #  The Tkinter.Label that is used to display the preview image
00323     
00324     ## @var raiting
00325     #  Tkinter variable the stores the currently selected raiting value (in range 1 to 6)
00326     
00327     ## @var sql_db
00328     #  When the frame is generated it tries to connectoct to the image information database (class image_information.SQLImageDatabase) - however if opening the database failed it is set to None
00329     
00330     ## @var tk_img
00331     #  We have to keep a pointer to the Tk.PhotoImage (preview image) or python will destroy it even it is used in a frame...
00332     
00333     ## @var as_py_image
00334     #  stores the image (original image with applied filters) as python image (in RGB format)
00335         
00336     ## @brief This method is called when the users presses the "Rate" Button.
00337     #  @param self the object pointer
00338     #
00339     #  If there's an open connection to the sql database the new information is stored. If anything wents wrong an Error message is displayed.
00340     def _rate_callback(self):
00341         if self.sql_db is None:
00342             tkMessageBox.showerror(message="You don't have a image information database connection - so you can't rate images!", parent=self, title="Error")
00343             return
00344         try:
00345             self.sql_db.add_image(self.orignal_image_as_cvM, self.raiting.get(), self.list_areas)
00346         except Exception as e:
00347             tkMessageBox.showerror(message="Can't add new data to database.\nThis is really strange...", parent=self, title="Error")
00348             print(e)
00349         self.sql_db.get_images()
00350     
00351     ## @brief This method checks which image area is selected and sets the value of the sliders according to the values stored in the settings of the selected area.
00352     #  @param self the object pointer
00353     def _init_area_values(self):
00354         selected_area = self.areas[self.area_selection.get()]
00355         for _filter in selected_area.filters:
00356             # look up which filter we have and then set all of it's parameters
00357             if _filter.name == "GaussianBlur":
00358                 for parameter in _filter.parameters:
00359                     if parameter.name == "blurwidth":
00360                         self.blur_width.set(int(parameter.value))
00361                     elif parameter.name == "blurheight":
00362                         self.blur_height.set(int(parameter.value))
00363             elif _filter.name == "Canny":
00364                 for parameter in _filter.parameters:
00365                     if parameter.name == "threshold1":
00366                         self.c_threshold1.set(parameter.value)
00367                     elif parameter.name == "threshold2":
00368                         self.c_threshold2.set(parameter.value)
00369             elif _filter.name == "DeleteShortLines":
00370                 for parameter in _filter.parameters:
00371                     if parameter.name == "minNumPixels":
00372                         self.min_length.set(parameter.value)
00373             elif _filter.name == "EdgeConnector":
00374                 for parameter in _filter.parameters:
00375                     if parameter.name == "searchRadius":
00376                         self.s_radius.set(parameter.value)
00377                       
00378         ## @brief This method calculates the position of the selected image area according to new x and y positions. The positions are adjusted so that they cover an legal part of the image.
00379         #  @param self the object pointer
00380         #  @param x_center new supposed center x-position of the selected area
00381         #  @param y_center new supposed center y-position of the selected area
00382         #  @return left, top, width, height: left is the left bounding of the area, top is the upper bounding of the area and width and height are the width and height of the area
00383     def _adjust_positions(self, x_center, y_center):
00384         selected_area = self.areas[self.area_selection.get()]
00385         width, height = selected_area.area.width, selected_area.area.height
00386         half_width, half_height = int(width / 2.0), int(height / 2.0)
00387         left, right, top, down = x_center - half_width, x_center + half_width, y_center - half_height, y_center + half_height
00388         img_width, img_height = self.as_py_image.size
00389         if left < 0:
00390             left = 0
00391             right = width
00392         if top < 0:
00393             top = 0
00394             down = height
00395         if right > img_width - 1:
00396             right = img_width
00397             left = img_width - width
00398         if down > img_height - 1:
00399             down = img_height
00400             top = img_height - height
00401         return left, top, width, height
00402     
00403     ## @brief Callback function when the users clicks inside the preview image.
00404     #  @param self the object pointer
00405     #  @param evt the mouse event
00406     #
00407     #  Calculates the new position of the selected area and sets its values. It also forces a redraw of the preview. 
00408     def _mouse_click_callback(self, evt):
00409         left, top, width, height = self._adjust_positions(evt.x, evt.y)
00410         selected_area = self.areas[self.area_selection.get()]
00411         selected_area.area.x, selected_area.area.y = left, top
00412         self._apply_and_display()
00413         
00414     ## @brief Callback function whe the users moves the mouse inside the preview image
00415     #  @param self the object pointer
00416     #  @param evt the mouse event
00417     #
00418     #  Function is used to update the preview image so that the blue box, indicating the new position of the area, is displayed correctly.
00419     #  Draws the blue box inside the current image without decoration (as_py_image).
00420     def _mouse_motion_callback(self, evt):
00421         left, top, width, height = self._adjust_positions(evt.x, evt.y)
00422         blue = 0, 0, 255
00423         self._set_display_image( self._draw_area(self.as_py_image, left, top, width, height, blue))
00424     
00425     ## @brief Set the preview image.
00426     #  @param self the object pointer
00427     #  @param img the new image as python image
00428     #
00429     #  Converts the python image to a Tk Image and keeps a reference to the image so that it is not destroyed by python.
00430     def _set_display_image(self, img):
00431         # convert to tkinter image
00432         tk_img = ImageTk.PhotoImage(img)
00433         # keep reference
00434         self.tk_img = tk_img
00435         self.image_label.configure(image=tk_img)
00436     
00437     ## @brief Callback function for the OptionMenu (selected area has changed).
00438     #  @param self the object pointer
00439     #  @param *args whatever arguments are passed
00440     #
00441     #  Set the slider values to the values of the new area and display the image again to draw the rectangles and so on
00442     def _area_selection_callback(self, *args):
00443         self._init_area_values()
00444         self._apply_and_display()
00445     
00446     ## @brief Callback function when the "Commit" button is pressed
00447     #  @param self the object pointer
00448     #
00449     #  Destroys the master of this frame (usually a Tkinter.Toplevel). The gui_serivce now calls the main gui and transfers the edge image.
00450     def _commit(self):
00451         self.master.destroy()
00452     
00453     ## @brief For the selected area save all parameter values (from the sliders) and set the fields of the filter objects.
00454     #  @param self the object pointer
00455     #  @param parameter_name the new of the parameter that has changed and so called this method to set the parameters.
00456     #
00457     #  This method is used to copy the values from the sliders to the filter objects.  
00458     def _set_parameter_values(self, parameter_name):
00459         selected_area = self.areas[self.area_selection.get()]
00460         # set for this area all parameters
00461         for _filter in selected_area.filters:
00462             # look up which filter we have and then set all of it's parameters
00463             if _filter.name == "GaussianBlur":
00464                 for parameter in _filter.parameters:
00465                     if parameter_name == "blurwidth" and parameter.name == "blurwidth":
00466                         parameter.value = str(self.blur_width.get()).encode("ascii")
00467                     elif parameter_name == "blurheight" and parameter.name == "blurheight":
00468                         parameter.value = str(self.blur_height.get()).encode("ascii")
00469             elif _filter.name == "Canny":
00470                 for parameter in _filter.parameters:
00471                     if parameter_name == "threshold1" and parameter.name == "threshold1":
00472                         parameter.value = str(self.c_threshold1.get()).encode("ascii")
00473                     elif parameter_name == "threshold2" and parameter.name == "threshold2":
00474                         parameter.value = str(self.c_threshold2.get()).encode("ascii")
00475             elif _filter.name == "DeleteShortLines":
00476                 for parameter in _filter.parameters:
00477                     if parameter_name == "minNumPixels" and parameter.name == "minNumPixels":
00478                         parameter.value = str(self.min_length.get()).encode("ascii")
00479             elif _filter.name == "EdgeConnector":
00480                 for parameter in _filter.parameters:
00481                     if parameter_name == "searchRadius" and parameter.name == "searchRadius":
00482                         parameter.value = str(self.s_radius.get()).encode("ascii")           
00483     
00484     ## @brief Callback function if on of the sliders or the text field content changed
00485     #  @param self the object pointer
00486     #  @param parameter_name the name of the parameter that has changed
00487     #  @param *args whatever arguments are also passed
00488     #
00489     #  Updates all parameters, calculates the corresponding image (and sets current_image to the new image), draws area squares and displays the image
00490     def _parameter_value_changed(self, parameter_name, *args):
00491         self._set_parameter_values(parameter_name)
00492         if self.immediately_apply.get():
00493             self._apply_and_display()
00494     
00495     ## @brief Apply filter with current settings and display the resulting image.
00496     #  @param self the object pointer
00497     #  @param *args whatever arguments are also passed
00498     def _apply_and_display(self, *args):
00499         self._apply_filters()
00500         self._draw_selected_area()
00501         self._set_display_image(self.as_py_image)
00502     
00503     ## @brief Just apply the filters with current settings and update the pointers of the images that are used in this class.
00504     #  @param self the object pointer
00505     #  @param *args whatever arguments are also passed
00506     def _apply_filters(self, *args):
00507         # apply the filters
00508         f = rospy.ServiceProxy("apply_filters", ApplyFilters)
00509         resp = f(self.original_image, self.list_areas)
00510         res = resp.result_image
00511         # set the global current image
00512         global current_image
00513         current_image = res
00514         # generate a python image of the result
00515         img = cv.CloneMat(self.bridge.imgmsg_to_cv(res))
00516         img = Image.fromstring("L", cv.GetSize(img), img.tostring())
00517         img = img.convert("RGB")
00518         self.as_py_image = img
00519     
00520     ## @brief callback function if the immediately apply changes value changed
00521     #  @param self the object pointer
00522     #  @param *args whatever arguments are also passed
00523     #
00524     #  If the immediately apply value changed to True we should apply the filters right now and display the new image.
00525     def _immediately_callback(self, *args):
00526         if self.immediately_apply.get():
00527             self._apply_filters(args)
00528     
00529     ## @brief Draw in img a rectangle from positon x, y with respective width and height in color.
00530     #  @param self the object pointer
00531     #  @param img PIL image in which the area is drawn
00532     #  @param x x-position of the start point
00533     #  @param y y-position of the start point
00534     #  @param width width of the rectangle
00535     #  @param height height of the rectangle
00536     #  @param color RGB color (three tuple) defining the color of the rectangle
00537     #  @return A copy of this image containing the rectangle
00538     def _draw_area(self, img, x, y, width, height, color):
00539         copy = img.copy()
00540         x_range = range(x, x + width)
00541         y_range = range(y, y + height)
00542         for i in x_range:
00543             copy.putpixel((i, y), color)
00544             copy.putpixel((i, y + height - 1), color)
00545         for i in y_range:
00546             copy.putpixel((x, i), color)
00547             copy.putpixel((x + width - 1, i), color)
00548         return copy
00549      
00550      ## @brief draw the rectangle for the currently selected area
00551      #  @param self the object pointer   
00552     def _draw_selected_area(self):
00553         selected_area = self.areas[self.area_selection.get()]
00554         x, y, width, height = selected_area.area.x, selected_area.area.y, selected_area.area.width, selected_area.area.height
00555         red = 255, 0, 0
00556         self.as_py_image = self._draw_area(self.as_py_image, x, y, width, height, red)
00557 
00558 ## @brief Calculate appropriate interval for the sliders.
00559 #  @param min_ the minimum value of the slider
00560 #  @param max_ the maximum value of the slider
00561 #  @param tick_count the amount of ticks on the slider. If omitted 4 is used.
00562 def _slider_tickinterval(min_, max_, tick_count=None):
00563     if tick_count is None:
00564         tick_count = 4
00565     dif = max_ - min_ + 1
00566     if dif < 0:
00567         return 1
00568     else:
00569         return int(dif / tick_count)
00570 
00571 ## @brief Transform a sensor_msgs/Image to a ImageTk.PhotoImage. Image is transformed to a "mono8" photo.
00572 def imgmsg_to_photo_image(imgmsg_img, bridge):
00573     cv_img = bridge.imgmsg_to_cv(imgmsg_img, "mono8")
00574     return ImageTk.PhotoImage( Image.fromstring("L", cv.GetSize(cv_img), cv_img.tostring()) )
 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