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 import roslib
00035 roslib.load_manifest('qualification')
00036 import rospy
00037
00038 import numpy
00039 import matplotlib
00040 import matplotlib.pyplot as plot
00041 import sys
00042 from StringIO import StringIO
00043 import threading
00044 import time
00045
00046 from sensor_msgs.msg import LaserScan
00047 from pr2_self_test_msgs.srv import TestResult, TestResultRequest
00048 from pr2_self_test_msgs.msg import Plot
00049
00050 from optparse import OptionParser
00051
00052 def bool_to_msg(bool_val):
00053 if bool_val:
00054 return 'OK'
00055 return 'FAIL'
00056
00057 class TestParams:
00058 def __init__(self):
00059
00060 self.transpose = False
00061
00062 self.ok_noise = 0.06
00063 self.histlen = 10
00064 self.plotinterval = 5
00065
00066 self.skip_count = 20
00067
00068
00069
00070 class LongRangeParams(TestParams):
00071 def __init__(self):
00072 TestParams.__init__(self)
00073
00074 self.ok_err = 4.0
00075 self.ok_maxerr = 5.0
00076
00077 self.tgt_a = 0
00078 self.ok_a = numpy.tan(60.0 * numpy.pi / 180)
00079 self.tgt_b = 9.0
00080 self.ok_b = 3.0
00081
00082
00083 self.min_ang = -15 * numpy.pi / 180
00084 self.max_ang = -3 * numpy.pi / 180
00085
00086 class MidRangeParams(TestParams):
00087 def __init__(self):
00088 TestParams.__init__(self)
00089
00090
00091 self.transpose = True
00092
00093 self.ok_err = .05
00094 self.ok_maxerr = .1
00095 self.tgt_a = 0
00096 self.ok_a = numpy.tan(3.0 * numpy.pi / 180)
00097 self.tgt_b = 1.90
00098 self.ok_b = .10
00099 self.min_ang = -110 * numpy.pi / 180
00100 self.max_ang = -70 * numpy.pi / 180
00101
00102 class ShortRangeParams(TestParams):
00103 def __init__(self):
00104 TestParams.__init__(self)
00105
00106 self.transpose = True
00107
00108 self.ok_err = .01
00109 self.ok_maxerr = .02
00110 self.tgt_a = 0
00111 self.ok_a = numpy.tan(10.0 * numpy.pi / 180)
00112 self.tgt_b = -0.04
00113 self.ok_b = 0.04
00114 self.min_ang = 70 * numpy.pi / 180
00115 self.max_ang = 110 * numpy.pi / 180
00116
00117
00118 class HokuyoTest:
00119 def __init__(self, topic, param):
00120 self._mutex = threading.Lock()
00121
00122 rospy.init_node('hokuyo_test')
00123 rospy.Subscriber(topic, LaserScan, self.callback)
00124 self.result_service = rospy.ServiceProxy('/test_result', TestResult)
00125 self.skipped = 0
00126 self.param = param
00127 self.xhist = []
00128 self.yhist = []
00129 self.rhist = []
00130 self.ihist = []
00131
00132 self.plot_index = 0
00133
00134 self.rec_count = 0
00135
00136 self.data_sent = False
00137
00138
00139 def plotdata(self, x, y, a, b):
00140 self.plot_index += 1
00141 fig = plot.figure(self.plot_index)
00142 plot.ylabel('Y data')
00143 plot.xlabel('X data')
00144
00145 plot.plot(x, y, 'b--', label='Data')
00146
00147 plot.axhline(y = self.param.tgt_b, color = 'g', label='Expected')
00148 fig.text(.38, .95, 'Hokuyo Range Data')
00149 plot.legend(shadow=True)
00150
00151
00152
00153 stream = StringIO()
00154 plot.savefig(stream, format="png")
00155 image = stream.getvalue()
00156 p = Plot()
00157 p.title = 'range_data'
00158 p.image = image
00159 p.image_format = 'png'
00160
00161 return p
00162
00163
00164 def test_failed_service_call(self, except_str = ''):
00165 rospy.logerr(except_str)
00166 r = TestResultRequest()
00167 r.html_result = except_str
00168 r.text_summary = 'Caught exception, automated test failure.'
00169 r.plots = []
00170 r.result = TestResultRequest.RESULT_FAIL
00171 self.send_results(r)
00172
00173
00174 def send_results(self, test_result):
00175 if self.data_sent:
00176 return
00177
00178 rospy.wait_for_service('/test_result', 15)
00179 self.result_service.call(test_result)
00180 self.data_sent = True
00181
00182 def plotintensity(self, x, intensity):
00183 self.plot_index += 1
00184 fig = plot.figure(self.plot_index)
00185 plot.ylabel('Intensity')
00186 plot.xlabel('X value')
00187 plot.plot(x, intensity, 'b--', label='Data')
00188
00189 fig.text(.38, .95, 'Hokuyo Intensity Data')
00190
00191
00192
00193 stream = StringIO()
00194 plot.savefig(stream, format="png")
00195 image = stream.getvalue()
00196 p = Plot()
00197 p.title = 'intensity_data'
00198 p.image = image
00199 p.image_format = 'png'
00200
00201 return p
00202
00203
00204
00205 def callback(self, data):
00206 if self.data_sent:
00207 return
00208
00209 self.rec_count += 1
00210 if self.rec_count < self.param.skip_count:
00211 return
00212
00213 self._mutex.acquire()
00214
00215 angles = numpy.arange(data.angle_min, data.angle_max, data.angle_increment);
00216 ranges = numpy.array(data.ranges)
00217 intensities = numpy.array(data.intensities)
00218
00219
00220 xvals = []
00221 yvals = []
00222 rvals = []
00223 ivals = []
00224 for i in range(0,len(angles)):
00225 if angles[i] < self.param.min_ang or angles[i] > self.param.max_ang:
00226 continue
00227
00228 if self.param.transpose:
00229 xvals.append(numpy.cos(angles[i])*ranges[i])
00230 yvals.append(-numpy.sin(angles[i])*ranges[i])
00231 else:
00232 xvals.append(-numpy.sin(angles[i])*ranges[i])
00233 yvals.append(numpy.cos(angles[i])*ranges[i])
00234
00235 rvals.append(ranges[i])
00236 ivals.append(intensities[i])
00237
00238
00239 self.xhist.append(xvals)
00240 self.yhist.append(yvals)
00241 self.rhist.append(rvals)
00242 self.ihist.append(ivals)
00243 self._mutex.release()
00244
00245
00246 def analyze_data(self):
00247 self._mutex.acquire()
00248
00249 mean_f = lambda l:sum(l)/len(l)
00250 xmean = map(mean_f,zip(*self.xhist))
00251 ymean = map(mean_f,zip(*self.yhist))
00252 imean = map(mean_f,zip(*self.ihist))
00253
00254 square_f = lambda l: map(lambda x: pow(x,2),l)
00255
00256 rhistt = zip(*self.rhist)
00257 r2histt = map(square_f, rhistt)
00258 r2mean = map(mean_f,r2histt)
00259 rmean = map(mean_f,rhistt)
00260
00261
00262 (a,b) = numpy.polyfit(xmean, ymean, 1)
00263
00264
00265 err = numpy.sqrt(sum(map(lambda x,y: (y-(a*x+b))**2, xmean, ymean))/ len(xmean))
00266 maxerr = numpy.sqrt(max(map(lambda x,y: (y-(a*x+b))**2, xmean, ymean)))
00267
00268
00269 err_ok = err < self.param.ok_err
00270 maxerr_ok = maxerr < self.param.ok_maxerr
00271 angle_ok = abs(self.param.tgt_a - a) < self.param.ok_a
00272 range_ok = abs(self.param.tgt_b - b) < self.param.ok_b
00273
00274 table_error = '<table border="1" cellpadding="2" cellspacing="0">\n'
00275 table_error += '<tr><td><b>Param</b></td><td><b>Message</b></td><td><b>Value</b></td><td><b>Tolerance</b></td></tr>\n'
00276 table_error += '<tr><td>Std. Dev. of Wall</td><td>%s</td><td>%.3f</td><td>%.3f</td></tr>\n' % (bool_to_msg(err_ok), err, self.param.ok_err)
00277 table_error += '<tr><td>Max Error of Wall</td><td>%s</td><td>%.3f</td><td>%.3f</td></tr>\n' % (bool_to_msg(maxerr_ok), maxerr, self.param.ok_maxerr)
00278 table_error += '</table>\n'
00279
00280
00281 table_range = '<table border="1" cellpadding="2" cellspacing="0">\n'
00282 table_range += '<tr><td><b>Param</b></td><td><b>Message</b></td><td><b>Value</b></td><td><b>Expected</b></td><td><b>Tolerance</b></td></tr>\n'
00283
00284 table_range += '<tr><td>Angle of Wall</td><td>%s</td><td>%.2f</td><td>%.2f</td><td>%.2f</td></tr>\n' % (bool_to_msg(angle_ok), a, self.param.tgt_a, self.param.ok_a)
00285 table_range += '<tr><td>Range of Wall</td><td>%s</td><td>%.2f</td><td>%.2f</td><td>%.2f</td></tr>\n' % (bool_to_msg(range_ok), b, self.param.tgt_b, self.param.ok_b)
00286 table_range += '</table>\n'
00287
00288 html = '<img src=\"IMG_PATH/range_data.png\", width=640, height=480 />'
00289 html += table_error + '<br><br>\n' + table_range + '<br>\n'
00290 html += '<img src=\"IMG_PATH/intensity_data.png\", width=640, height=480 />'
00291
00292
00293 r = TestResultRequest()
00294
00295
00296 all_ok = err_ok and maxerr_ok and angle_ok and range_ok
00297
00298 if all_ok:
00299 r.result = TestResultRequest.RESULT_PASS
00300 r.text_summary = 'Hokuyo range test: PASS'
00301 else:
00302 r.result = TestResultRequest.RESULT_FAIL
00303 r.text_summary = 'Hokuyo range test failed. Error: %s, Max error: %s, Angle: %s, Range: %s' % \
00304 (bool_to_msg(err_ok), bool_to_msg(maxerr_ok), bool_to_msg(angle_ok), bool_to_msg(range_ok))
00305
00306
00307 r.plots = [ self.plotdata(xmean, ymean, a, b), self.plotintensity(xmean, imean) ]
00308
00309 r.html_result = html
00310
00311 self.send_results(r)
00312
00313
00314 self._mutex.release()
00315
00316
00317 if __name__ == '__main__':
00318 parser = OptionParser(usage="./%prog [options]. Either short-, mid- or long- range.", prog="hokuyo_test.py")
00319 parser.add_option("--long", action="store_true", dest="long", default=False, metavar="LONGRANGE",
00320 help="Long range test")
00321 parser.add_option("--mid", action="store_true", dest="mid", default=False, metavar="MIDRANGE",
00322 help="Mid range test")
00323 parser.add_option("--short", action="store_true", dest="short", default=False, metavar="SHORTRANGE",
00324 help="Short range test")
00325
00326 options, args = parser.parse_args()
00327
00328 multi_msg = "Options --short, --mid and --long are mutually exclusive"
00329
00330 if not options.long and not options.mid and not options.short:
00331 parser.error("Must select a range to test")
00332 if options.long and options.mid:
00333 parser.error(multi_msg)
00334 if options.long and options.short:
00335 parser.error(multi_msg)
00336 if options.short and options.mid:
00337 parser.error(multi_msg)
00338
00339
00340 if options.long:
00341 ht = HokuyoTest('scan', LongRangeParams())
00342 elif options.mid:
00343 ht = HokuyoTest('scan', MidRangeParams())
00344 else:
00345 ht = HokuyoTest('scan', ShortRangeParams())
00346
00347 try:
00348 while len(ht.xhist) < ht.param.histlen and not rospy.is_shutdown():
00349 time.sleep(1)
00350 ht.analyze_data()
00351 except KeyboardInterrupt:
00352 raise
00353 except:
00354 import traceback
00355 rospy.logerr('Exception in hokuyo range test.\n%s' % traceback.format_exc())
00356 ht.test_failed_service_call(traceback.format_exc())
00357
00358