00001
00002 import sqlite3
00003 import roslib
00004 roslib.load_manifest('face_contour_detector')
00005 import rospy
00006 import os
00007 import image_information
00008 import cv
00009 import cv_bridge
00010 from face_contour_detector.srv import *
00011 from face_contour_detector.msg import *
00012
00013
00014
00015
00016
00017 MAX_IMAGE_SIZE = 50000
00018
00019
00020
00021
00022
00023
00024 class SQLImageDatabase:
00025 def __init__(self, bridge=None):
00026 if bridge is None:
00027 bridge = cv_bridge.CvBridge()
00028 self.bridge = bridge
00029 self.connection = None
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043 def load_file(self, file_name=None):
00044 if file_name is None:
00045 pkg_dir = roslib.packages.get_pkg_dir("face_contour_detector")
00046 data_dir = os.path.join(pkg_dir, "data")
00047
00048 if not os.path.exists(data_dir):
00049 try:
00050 os.mkdir(data_dir)
00051 rospy.loginfo("created directory " + data_dir + " required for image information database")
00052 except Exception as e:
00053 rospy.logerr("cant create directory " + data_dir + " required for image information database")
00054 raise e
00055 file_name = os.path.join(data_dir, "image_information.db")
00056
00057 existed = os.path.exists(file_name)
00058 if not existed:
00059 rospy.loginfo("no database found. Try to create new one...")
00060 try:
00061 self.connection = sqlite3.connect(file_name)
00062 rospy.loginfo("opened / created image information database " + file_name)
00063 except Exception as e:
00064 rospy.logerr("unable to open / generate image information database file " + file_name)
00065 raise e
00066 if not existed:
00067 self._create_tables()
00068 return existed
00069
00070
00071
00072 def _create_tables(self):
00073 cmd = """
00074 CREATE TABLE images
00075 (id INTEGER PRIMARY KEY,
00076 brightness FLOAT,
00077 brightness_sdeviation FLOAT,
00078 raiting INT
00079 )"""
00080 self.connection.execute(cmd)
00081 cmd = """
00082 CREATE TABLE image_areas
00083 (
00084 image_id INTEGER,
00085 area_name TEXT,
00086 blur_width INTEGER,
00087 blur_height INTEGER,
00088 c_threshold1 FLOAT,
00089 c_threshold2 FLOAT
00090 )"""
00091 self.connection.execute(cmd)
00092 self.connection.commit()
00093
00094
00095
00096
00097
00098
00099 def add_image(self, image, raiting, areas):
00100 extractor = image_information.InformationExtractor()
00101 extractor.information_extractors = [ image_information.AverageValueExtractor() ]
00102 information = extractor.to_dict(image)
00103 cmd = "SELECT COUNT(*) FROM images"
00104 cursor = self.connection.execute(cmd)
00105 count = None
00106
00107 for row in cursor:
00108 count = row[0]
00109 rospy.loginfo("Image database contains information about " + str(count) + " images")
00110
00111 if count >= MAX_IMAGE_SIZE:
00112 cmd = "SELECT id FROM images LIMIT 1"
00113 cursor = self.connection.execute(cmd)
00114 delete_id = None
00115
00116 for row in cursor:
00117 delete_id = row[0]
00118
00119 cmd = "DELETE FROM images WHERE id = ?"
00120 self.connection.execute(cmd, (delete_id,))
00121 cmd = "DELETE FROM image_areas WHERE image_id = ?"
00122 self.connection.execute(cmd, (delete_id,))
00123 t = information["AveragePixelBrightness"][0], information["StandardBrightnessDeviation"][0], raiting
00124 cmd = """
00125 INSERT INTO images (brightness, brightness_sdeviation, raiting)
00126 VALUES(?, ?, ?)
00127 """
00128 cursor = self.connection.execute(cmd, t)
00129 _id = cursor.lastrowid
00130 for area in areas:
00131 blur_width, blur_height, treshold1, threshold2 = None, None, None, None
00132 for _filter in area.filters:
00133 if _filter.name == "GaussianBlur":
00134 blur_width, blur_height = 0, 0
00135 for parameter in _filter.parameters:
00136 if parameter.name == "blurwidth":
00137 blur_width = int(parameter.value)
00138 elif parameter.name == "blurheight":
00139 blur_height = int(parameter.value)
00140 elif _filter.name == "Canny":
00141 for parameter in _filter.parameters:
00142 if parameter.name == "threshold1":
00143 threshold1 = float(parameter.value)
00144 elif parameter.name == "threshold2":
00145 threshold2 = float(parameter.value)
00146 cmd = "INSERT INTO image_areas (image_id, area_name, blur_width, blur_height, c_threshold1, c_threshold2) VALUES (?, ?, ?, ?, ?, ?)"
00147 t = _id, area.area.name, blur_width, blur_height, threshold1, threshold2
00148 self.connection.execute(cmd, t)
00149 self.connection.commit()
00150
00151
00152 def _apply_filter(self, image, areas):
00153 img_msg = self.bridge.cv_to_imgmsg(image)
00154 f = rospy.ServiceProxy("apply_filters", ApplyFilters)
00155 resp = f(img_msg, areas)
00156 return self.bridge.imgmsg_to_cv(resp.result_image, "mono8")
00157
00158
00159
00160
00161
00162
00163
00164
00165 def get_images(self):
00166 cmd = """
00167 SELECT * FROM images
00168 """
00169 cursor = self.connection.execute(cmd)
00170 images = []
00171 for _id, brightness, brightness_sderivation, raiting in cursor:
00172
00173 image = {}
00174 image["AveragePixelBrightness"] = brightness
00175 image["StandardBrightnessDeviation"] = brightness_sderivation
00176 image["Raiting"] = raiting
00177 image["Areas"] = areas = {}
00178
00179 cmd = """
00180 SELECT * FROM image_areas WHERE image_id = ?
00181 """
00182 cursor2 = self.connection.execute(cmd, (_id,))
00183 for image_id, name, blur_width, blur_height, threshold1, threshold2 in cursor2:
00184 area = {}
00185 area["blurwidth"] = blur_width
00186 area["blurheight"] = blur_height
00187 area["threshold1"] = threshold1
00188 area["threshold2"] = threshold2
00189 areas[name] = area
00190 images.append(image)
00191 return images