00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039 from __future__ import with_statement
00040
00041 PKG = 'qualification'
00042 import roslib
00043 roslib.load_manifest(PKG)
00044 import sys
00045 import rospy
00046 import cv
00047 from std_msgs.msg import String
00048 from sensor_msgs.msg import Image
00049 from cv_bridge import CvBridge, CvBridgeError
00050 import subprocess
00051 from time import sleep
00052 from pr2_self_test_msgs.srv import *
00053 from diagnostic_msgs.msg import *
00054 import wx
00055 import time
00056
00057 class BayerDetector:
00058 def __init__(self, done_cb, red_source):
00059 self.status = "Waiting for first image."
00060 self.done_cb = done_cb
00061 self.red_source = red_source
00062 self.bridge = CvBridge()
00063 self.maxdim = -1
00064 self.bw_scaling = cv.CreateMat(2, 2, cv.CV_32FC1)
00065 self.bw_scaling[0,0] = 1
00066 self.bw_scaling[0,1] = 1
00067 self.bw_scaling[1,0] = 1
00068 self.bw_scaling[1,1] = 1
00069 self.col_scaling = cv.CreateMat(2, 2, cv.CV_32FC1)
00070 if red_source:
00071 self.col_scaling[0,0] = .50
00072 self.col_scaling[0,1] = 1.04
00073 self.col_scaling[1,0] = 1.04
00074 self.col_scaling[1,1] = 1.40
00075 else:
00076 self.col_scaling[0,0] = .82
00077 self.col_scaling[0,1] = .91
00078 self.col_scaling[1,0] = .91
00079 self.col_scaling[1,1] = 1.36
00080 self.detected = False
00081 self.image_sub = rospy.Subscriber("camera/image_raw", Image, self.process_image)
00082
00083 def process_image(self, image):
00084 wx.CallAfter(self.process_image_main_thread, image)
00085
00086 def process_image_main_thread(self, image):
00087 try:
00088 image.encoding = "mono8"
00089 cv_image = self.bridge.imgmsg_to_cv(image, "mono8")
00090 except CvBridgeError, e:
00091 import traceback
00092 traceback.print_exc()
00093
00094 (width, height) = cv.GetSize(cv_image)
00095
00096 origimg = cv.CreateMat(height, width, cv.CV_32FC1)
00097 cv.Scale(cv_image, origimg, 4.0 / (width * height), 0.0)
00098
00099 maxdim = max(width, height)
00100 if maxdim > self.maxdim:
00101
00102
00103 self.checker = cv.CreateMat(2, maxdim, cv.CV_32FC1)
00104 for x in range(maxdim):
00105 self.checker[0,x] = 1 if x % 2 else 0
00106 self.checker[1,x] = 1 - self.checker[0, x]
00107 self.maxdim = maxdim
00108
00109 rowmult = cv.GetSubRect(self.checker, (0, 0, height, 2))
00110 colmult = cv.GetSubRect(self.checker, (0, 0, width, 2))
00111
00112 tmp = cv.CreateMat(height, 2, cv.CV_32FC1)
00113 cv.GEMM(origimg, colmult, 1, None, 0, tmp, cv.CV_GEMM_B_T)
00114
00115 out = cv.CreateMat(2, 2, cv.CV_32FC1)
00116 cv.GEMM(rowmult, tmp, 1, None, 0, out, 0)
00117
00118 if self.try_match(out, self.bw_scaling):
00119 self.detected_type = 'mono'
00120 self.status = "mono"
00121 self.detected = True
00122 print "BW: ", self.status,
00123 if self.try_match(out, self.col_scaling):
00124 self.detected_type = 'color'
00125 self.status = "color"
00126 self.detected = True
00127 print "Col: ", self.status
00128
00129 if self.detected:
00130 self.done_cb()
00131 self.image_sub.unregister()
00132
00133
00134
00135 def try_match(self, out, scaling):
00136 tmp = cv.CreateMat(2, 2, cv.CV_32FC1)
00137 cv.Mul(out, scaling, tmp)
00138 avg, _ = cv.AvgSdv(tmp)
00139 avg = avg[0]
00140 dev = 0
00141 for x in range(2):
00142 for y in range(2):
00143 dev = max(dev, abs(tmp[x,y] - avg))
00144 print
00145 for i in range(2):
00146 for j in range(2):
00147 print tmp[i, j],
00148 print
00149 print
00150 print avg, dev, dev/avg
00151 if avg < 16:
00152 self.status = "Too dark. (%i)"%int(avg)
00153 elif avg > 192:
00154 self.status = "Too bright. (%i)"%int(avg)
00155 elif dev / avg < 0.1:
00156 self.status = "Match!"
00157 return True
00158 else:
00159 if self.red_source:
00160 self.status = "Camera should be pointing at the red LED."
00161 else:
00162 self.status = "Point camera at white target."
00163 return False
00164
00165 class ModelDetector:
00166 def __init__(self, done_cb):
00167 self.status = "Waiting for model number."
00168 self.model = None
00169 self.done_cb = done_cb
00170 rospy.Subscriber('/diagnostics', DiagnosticArray, self.msg_cb)
00171
00172 def msg_cb(self, msg):
00173 wx.CallAfter(self.msg_cb_main_thread, msg)
00174
00175 def msg_cb_main_thread(self, msg):
00176 for s in msg.status:
00177 if s.name == 'wge100_camera: Driver Status':
00178 for kv in s.values:
00179 if kv.key == 'Imager model':
00180 self.model = kv.value
00181 self.status = "Found model: %s"%self.model
00182 self.done_cb()
00183
00184 acceptable_combinations = [
00185 ('6805018', 'color', 'MT9V032'),
00186 ('6805027', 'mono', 'MT9V034'),
00187 ('6805030', 'color', 'MT9V032'),
00188 ]
00189
00190 class MainWindow(wx.Frame):
00191 def __init__(self):
00192 wx.Frame.__init__(self, None, wx.ID_ANY, "WGE100 imager check",
00193 pos=(200, 200), size=(400, 200))
00194 sizer = wx.FlexGridSizer(0, 2, vgap = 1, hgap = 4)
00195 sizer.SetFlexibleDirection(wx.BOTH)
00196 sizer.AddGrowableCol(1,1)
00197
00198 sizer.Add(wx.StaticText(self, wx.ID_ANY, label="Imager model:"))
00199 self.imager_text = wx.TextCtrl(self, wx.ID_ANY, value="Unknown.")
00200 self.imager_text.SetEditable(False)
00201 sizer.Add(self.imager_text, 1, wx.ALL | wx.EXPAND)
00202
00203 sizer.Add(wx.StaticText(self, wx.ID_ANY, label="Detected color filter:"))
00204 self.color_text = wx.TextCtrl(self, wx.ID_ANY, value="Unknown.")
00205 self.color_text.SetEditable(False)
00206 sizer.Add(self.color_text, 1, wx.ALL | wx.EXPAND)
00207
00208 sizer.Add(wx.StaticText(self, wx.ID_ANY, label="Serial number prefix:"))
00209 self.barcode_text = wx.TextCtrl(self, wx.ID_ANY, value="Unknown.")
00210 self.barcode_text.SetEditable(False)
00211 self.barcode_text.SetBackgroundColour((0, 255, 0))
00212 sizer.Add(self.barcode_text, 1, wx.ALL | wx.EXPAND)
00213
00214 self.SetSizerAndFit(sizer)
00215 self.SetMinSize((self.GetSize()[0] + 200, 10))
00216 sizer.Layout()
00217 self.Show()
00218
00219 def main(args):
00220 bd = None
00221 md = None
00222 result_sent = []
00223
00224 def update_ui():
00225 frame.color_text.SetValue(bd.status)
00226 if not bd.detected:
00227 frame.color_text.SetBackgroundColour((255,0,0))
00228 else:
00229 frame.color_text.SetBackgroundColour((0,255,0))
00230 frame.imager_text.SetValue(md.status)
00231 if not md.model:
00232 frame.imager_text.SetBackgroundColour((255,0,0))
00233 else:
00234 frame.imager_text.SetBackgroundColour((0,255,0))
00235 frame.barcode_text.SetValue(barcode_prefix)
00236
00237 def done_cb():
00238 global app
00239 if result_sent:
00240 return
00241
00242 update_ui()
00243
00244 if not bd:
00245 return
00246 if not bd.detected:
00247 return
00248 if not md.model:
00249 return
00250
00251 r = TestResultRequest()
00252 if (barcode_prefix, bd.detected_type, md.model) in acceptable_combinations:
00253 r.text_summary = "Found acceptable imager."
00254 r.html_result = "<p>Test passed.</p>"
00255 r.result = TestResultRequest.RESULT_PASS
00256 else:
00257 r.text_summary = "Unacceptable imager."
00258 r.html_result = "<p>Test failed.</p>"
00259 r.result = TestResultRequest.RESULT_FAIL
00260 r.html_result += "<p>Imager model: %s</p>"%md.model
00261 r.html_result += "<p>Detected color filter: %s</p>"%bd.detected_type
00262 r.html_result += "<p>Serial number prefix: %s</p>"%barcode_prefix
00263 r.html_result += "<p></p>"
00264 r.html_result += "<p>Acceptable combinations:</p>"
00265 for barcode, filter, imager in acceptable_combinations:
00266 r.html_result += "<p>%s, %s, %s</p>"%(barcode, filter, imager)
00267
00268 rospy.loginfo("Test completed, waiting for result server.")
00269 result_service = rospy.ServiceProxy('test_result', TestResult)
00270 rospy.wait_for_service('test_result')
00271 result_service.call(r)
00272 result_sent.append(None)
00273 time.sleep(1)
00274 rospy.on_shutdown(app.AddPendingEvent(wx.ID_EXIT))
00275 app.Exit()
00276 print "Exit requested"
00277
00278 rospy.init_node('imager_checker')
00279 app = wx.PySimpleApp()
00280 rospy.on_shutdown(app.Exit)
00281 barcode_prefix = str(rospy.get_param('qual_item/serial'))[0:7]
00282 frame = MainWindow()
00283 bd = BayerDetector(done_cb, rospy.get_param('~red_source'))
00284 md = ModelDetector(done_cb)
00285 update_ui()
00286 try:
00287 app.MainLoop()
00288 except KeyboardInterrupt:
00289 print "Shutting down"
00290 except:
00291 rospy.signal_shutdown("Shutting down.")
00292 print "Shut down"
00293
00294 if __name__ == '__main__':
00295 main(sys.argv)