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 PKG = "qualification"
00034 import roslib; roslib.load_manifest(PKG)
00035
00036 import numpy
00037 import math
00038
00039 import sys
00040 import os
00041 import string
00042 from time import sleep
00043
00044
00045 import matplotlib
00046 matplotlib.use('Agg')
00047 import matplotlib.pyplot as plt
00048 from StringIO import StringIO
00049
00050 from pr2_self_test_msgs.msg import Plot, TestParam, TestValue
00051
00052 class HysteresisParameters(object):
00053 """
00054 Stores Hysteresis test parameters. Can output them as TestParams
00055 """
00056 def __init__(self):
00057 self.joint_name = None
00058
00059 self.pos_effort = None
00060 self.neg_effort = None
00061 self.range_max = None
00062 self.range_min = None
00063 self.slope = None
00064
00065 self.p_gain = None
00066 self.i_gain = None
00067 self.d_gain = None
00068 self.i_clamp = None
00069 self.max_effort = None
00070
00071 self.timeout = None
00072 self.velocity = None
00073 self.tolerance = None
00074 self.sd_max = None
00075
00076 def validate(self):
00077 if self.joint_name is None: return False
00078 if self.pos_effort is None: return False
00079 if self.neg_effort is None: return False
00080 if self.range_max is None: return False
00081 if self.range_min is None: return False
00082 if self.slope is None: return False
00083 if self.timeout is None: return False
00084 if self.velocity is None: return False
00085 if self.tolerance is None: return False
00086 if self.sd_max is None: return False
00087
00088
00089
00090 return True
00091
00092 def get_test_params(self):
00093 """
00094 \return [ TestParam ] :
00095 """
00096 test_params = []
00097
00098 test_params.append(TestParam("Joint Name", self.joint_name))
00099 test_params.append(TestParam("Positive Effort", str(self.neg_effort)))
00100 test_params.append(TestParam("Negative Effort", str(self.pos_effort)))
00101 test_params.append(TestParam("Max Range", str(self.range_max)))
00102 test_params.append(TestParam("Min Range", str(self.range_min)))
00103 test_params.append(TestParam("Slope", str(self.slope)))
00104 test_params.append(TestParam("Timeout", str(self.timeout)))
00105 test_params.append(TestParam("Velocity", str(self.velocity)))
00106 test_params.append(TestParam("Effort SD Max", str(self.sd_max)))
00107 test_params.append(TestParam("Effort Tolerance", str(self.tolerance)))
00108
00109
00110 if self.p_gain is not None:
00111 test_params.append(TestParam("P Gain", str(self.p_gain)))
00112 if self.i_gain is not None:
00113 test_params.append(TestParam("I Gain", str(self.i_gain)))
00114 if self.d_gain is not None:
00115 test_params.append(TestParam("D Gain", str(self.d_gain)))
00116 if self.i_clamp is not None:
00117 test_params.append(TestParam("I Clamp", str(self.i_clamp)))
00118
00119 return test_params
00120
00121 def get_test_value(name, value, minv, maxv):
00122 """
00123 Convert values to TestValue. Force converts all arguments to string.
00124 """
00125 return TestValue(str(name), str(value), str(minv), str(maxv))
00126
00127
00128 class HysteresisDirectionData(object):
00129 """
00130 Data for one direction in hysteresis test
00131 """
00132 def __init__(self, position, effort, velocity):
00133 self.range_max = max(position)
00134 self.range_min = min(position)
00135
00136 min_index = int(0.05 * len(position))
00137 max_index = int(0.95 * len(position))
00138
00139 self.position = numpy.array(position)[min_index: max_index]
00140 self.effort = numpy.array(effort) [min_index: max_index]
00141 self.velocity = numpy.array(velocity)[min_index: max_index]
00142
00143 class HysteresisTestData(object):
00144 """
00145 Data for hysteresis test
00146 """
00147 def __init__(self, positive_data, negative_data):
00148 self.positive = positive_data
00149 self.negative = negative_data
00150
00151 self.range_max = max(self.positive.range_max, self.negative.range_max)
00152 self.range_min = min(self.positive.range_min, self.negative.range_min)
00153
00154
00155 class HysteresisAnalysisResult(object):
00156 """Struct to store result data"""
00157 __slots__ = ['html', 'summary', 'result', 'values' ]
00158 def __init__(self):
00159 self.html = ''
00160 self.summary = ''
00161 self.result = False
00162 self.values = []
00163
00164
00165
00166
00167
00168
00169 def range_analysis(params, data):
00170 result = HysteresisAnalysisResult()
00171 if (params.range_max == 0 and params.range_min == 0):
00172 result.summary = 'Range: Continuous.'
00173 result.html = '<p>Continuous joint, no range data.</p>\n'
00174 result.result = True
00175 return result
00176
00177 min_obs = data.range_min
00178 max_obs = data.range_max
00179
00180 fail = '<div class="error">FAIL</div>'
00181 ok = '<div class="pass">OK</div>'
00182
00183 max_ok = True
00184 min_ok = True
00185 min_status = ok
00186 max_status = ok
00187
00188 if (min_obs > params.range_min):
00189 min_ok = False
00190 min_status = fail
00191
00192 if (max_obs < params.range_max):
00193 max_ok = False
00194 max_status = fail
00195
00196 result.result = min_ok and max_ok
00197
00198 result.summary = 'Range: FAIL.'
00199 if result.result:
00200 result.summary = 'Range: OK.'
00201
00202 if result.result:
00203 result.html = '<p>Range of motion: OK.</p>\n'
00204 elif max_ok and not min_ok:
00205 result.html = "<p>Mechanism did not reach expected minimum range.</p>\n"
00206 elif min_ok and not max_ok:
00207 result.html = "<p>Mechanism did not reach expected maximum range.</p>\n"
00208 else:
00209 result.html = "<p>Mechanism did not reach expected minimum or maximum range.</p>\n"
00210
00211 table = ['<table border="1" cellpadding="2" cellspacing="0">\n']
00212 table.append('<tr><td></td><td><b>Observed</b></td><td><b>Expected</b></td><td><b>Status</b></td></tr>\n')
00213 table.append('<tr><td>Maximum</td><td>%.3f</td><td>%.3f</td><td>%s</td></tr>\n' % (max_obs, params.range_max, max_status))
00214 table.append('<tr><td>Minimum</td><td>%.3f</td><td>%.3f</td><td>%s</td></tr>\n' % (min_obs, params.range_min, min_status))
00215 table.append('</table>\n')
00216
00217 result.html += ''.join(table)
00218
00219
00220 result.values.append(get_test_value('Max Range', max_obs, params.range_max, ''))
00221 result.values.append(get_test_value('Min Range', min_obs, '', params.range_min))
00222
00223 return result
00224
00225
00226
00227
00228
00229
00230
00231
00232
00233
00234
00235
00236 def effort_analysis(params, data):
00237 result = HysteresisAnalysisResult()
00238
00239 max_avg = numpy.average(data.positive.effort)
00240 min_avg = numpy.average(data.negative.effort)
00241 max_sd = numpy.std(data.positive.effort)
00242 min_sd = numpy.std(data.negative.effort)
00243
00244 effort_diff = abs(params.pos_effort - params.neg_effort)
00245 tolerance = params.tolerance * effort_diff
00246 sd_max = params.sd_max * effort_diff
00247
00248 max_ok = abs(max_avg - params.pos_effort) < tolerance
00249 min_ok = abs(min_avg - params.neg_effort) < tolerance
00250
00251 max_even = max_sd < sd_max
00252 min_even = min_sd < sd_max
00253
00254 summary = 'Effort: FAIL.'
00255 if max_ok and min_ok and max_even and min_even:
00256 html = ['<p>Efforts OK.</p>\n']
00257 summary = 'Effort: OK.'
00258 result.result = True
00259 elif max_ok and min_ok:
00260 html = ['<p>Efforts have acceptable average, but are uneven.</p>\n']
00261 elif max_avg - params.pos_effort > tolerance and params.neg_effort - min_avg > tolerance:
00262 html = ['<p>Effort is too high.</p>\n']
00263 elif max_avg - params.pos_effort < tolerance and params.neg_effort - min_avg < tolerance:
00264 html = ['<p>Effort is too low.</p>\n']
00265 else:
00266 html = ['<p>Efforts are outside acceptable parameters. See graphs.</p>\n']
00267
00268
00269 sd_min_percent = abs(min_sd / effort_diff) * 100
00270 sd_max_percent = abs(max_sd / effort_diff) * 100
00271
00272 if max_even:
00273 positive_sd_msg = '<div class="pass">OK</div>'
00274 else:
00275 positive_sd_msg = '<div class="warning">UNEVEN</div>'
00276
00277 if min_even:
00278 negative_sd_msg = '<div class="pass">OK</div>'
00279 else:
00280 negative_sd_msg = '<div class="warning">UNEVEN</div>'
00281
00282 if max_ok:
00283 positive_msg = '<div class="pass">OK</div>'
00284 else:
00285 positive_msg = '<div class="error">FAIL</div>'
00286
00287 if min_ok:
00288 negative_msg = '<div class="pass">OK</div>'
00289 else:
00290 negative_msg = '<div class="error">FAIL</div>'
00291
00292 html.append('<table border="1" cellpadding="2" cellspacing="0">\n')
00293 html.append('<tr><td><b>Name</b></td><td><b>Average</b></td><td><b>Expected</b></td><td><b>Status</b></td><td><b>SD %</b></td><td><b>Status</b></td></tr>\n')
00294 html.append('<tr><td>Positive</td><td>%.2f</td><td>%.2f</td><td>%s</td><td>%.2f</td><td>%s</td></tr>\n' % (max_avg, params.pos_effort, positive_msg, sd_max_percent, positive_sd_msg))
00295 html.append('<tr><td>Negative</td><td>%.2f</td><td>%.2f</td><td>%s</td><td>%.2f</td><td>%s</td></tr>\n' % (min_avg, params.neg_effort, negative_msg, sd_min_percent, negative_sd_msg))
00296 html.append('</table><br>\n')
00297 html.append('<p>Effort tolerance: %.2f. SD tolerance: %.1f percent</p>\n' % (tolerance, params.sd_max * 100))
00298
00299 result.html = ''.join(html)
00300 result.summary = summary
00301
00302 result.values = []
00303 result.values.append(get_test_value('Positive Effort Avg', max_avg, params.pos_effort - tolerance, params.pos_effort + tolerance))
00304 result.values.append(get_test_value('Positive Effort SD', max_sd, '', sd_max))
00305 result.values.append(get_test_value('Positive Effort SD Percent', sd_max_percent, '', params.sd_max))
00306
00307 result.values.append(get_test_value('Negative Effort Avg', min_avg, params.neg_effort - tolerance, params.neg_effort + tolerance))
00308 result.values.append(get_test_value('Negative Effort SD', min_sd, '', sd_max))
00309 result.values.append(get_test_value('Positive Effort SD Percent', sd_min_percent, '', params.sd_max))
00310
00311 return result
00312
00313
00314
00315
00316
00317 def velocity_analysis(params, data):
00318 html = ['<p>Search velocity: %.2f.</p><br>\n' % abs(params.velocity)]
00319
00320 pos_avg = numpy.average(data.positive.velocity)
00321 pos_sd = numpy.std(data.positive.velocity)
00322 pos_rms = math.sqrt(numpy.average( (data.positive.velocity - params.velocity) * (data.positive.velocity - params.velocity) ))
00323
00324 neg_avg = numpy.average(data.negative.velocity)
00325 neg_sd = numpy.std(data.negative.velocity)
00326 neg_rms = math.sqrt(numpy.average( (data.negative.velocity - params.velocity) * (data.negative.velocity - params.velocity) ))
00327
00328 html.append('<table border="1" cellpadding="2" cellspacing="0">\n')
00329 html.append('<tr><td></td><td><b>Average</b></td><td><b>Std. Dev.</b></td><td><b>RMS</b></td></tr>\n')
00330 html.append('<tr><td>Positive</td><td>%.2f</td><td>%.3f</td><td>%.3f</td></tr>\n' % (pos_avg, pos_sd, pos_rms))
00331 html.append('<tr><td>Negative</td><td>%.2f</td><td>%.3f</td><td>%.3f</td></tr>\n' % (neg_avg, neg_sd, neg_rms))
00332 html.append('</table>\n')
00333
00334 result = HysteresisAnalysisResult()
00335 result.result = True
00336 result.html = ''.join(html)
00337
00338 result.values.append(get_test_value('Positive Velocity Avg', pos_avg, '', ''))
00339 result.values.append(get_test_value('Positive Velocity SD', pos_sd, '', ''))
00340 result.values.append(get_test_value('Positive Velocity RMS', pos_rms, '', ''))
00341 result.values.append(get_test_value('Negative Velocity Avg',neg_avg, '', ''))
00342 result.values.append(get_test_value('Negative Velocity SD', neg_sd, '', ''))
00343 result.values.append(get_test_value('Negative Velocity RMS', neg_rms, '', ''))
00344
00345 return result
00346
00347
00348
00349
00350
00351
00352
00353
00354 def regression_analysis(params, data):
00355 result = HysteresisAnalysisResult()
00356
00357 A_pos = numpy.vstack([data.positive.position, numpy.ones(len(data.positive.position))]).T
00358 A_neg = numpy.vstack([data.negative.position, numpy.ones(len(data.negative.position))]).T
00359
00360
00361 a_max, b_max = numpy.linalg.lstsq(A_pos, data.positive.effort)[0]
00362 a_min, b_min = numpy.linalg.lstsq(A_neg, data.negative.effort)[0]
00363
00364
00365 slope_avg = 0.5 * (a_max + a_min)
00366 slope_diff = abs((a_max - a_min))
00367 slope_sd_tol = abs(params.slope * params.sd_max)
00368
00369 diff_ok = slope_diff < slope_sd_tol
00370 pos_ok = abs(params.slope - a_max) < slope_sd_tol
00371 neg_ok = abs(params.slope - a_min) < slope_sd_tol
00372
00373 tol_intercept = params.tolerance * (params.pos_effort - params.neg_effort)
00374 pos_int_ok = abs(b_max - params.pos_effort) < tol_intercept
00375 neg_int_ok = abs(b_min - params.neg_effort) < tol_intercept
00376
00377 slope_ok = diff_ok and pos_ok and neg_ok and pos_int_ok and neg_int_ok
00378
00379 ok_dict = {True: 'OK', False: 'FAIL'}
00380
00381 if slope_ok:
00382 result.summary = "Effort: OK"
00383 result.result = True
00384 else:
00385 result.summary = "Effort: FAIL"
00386
00387
00388 html = ['<p>Simple linear regression on the effort and position plot data. See tables below for slopes, intercepts of effort plot. Both the positive and negative slopes must be in tolerance, and the difference between slopes must be acceptable.</p>\n']
00389 html.append('<table border="1" cellpadding="2" cellspacing="0">\n')
00390 html.append('<tr><td><b>Name</b></td><td><b>Slope</b></td><td><b>Expected</b><td><b>Tolerance</b></td><td><b>Passed</b></td>\n')
00391 html.append('<tr><td>Positive</td><td>%.3f</td><td>%.3f</td><td>%.3f</td><td>%s</td></tr>\n' % (a_max, params.slope, slope_sd_tol, ok_dict[pos_ok]))
00392 html.append('<tr><td>Negative</td><td>%.3f</td><td>%.3f</td><td>%.3f</td><td>%s</td></tr>\n' % (a_min, params.slope, slope_sd_tol, ok_dict[neg_ok]))
00393 html.append('<tr><td>Difference</td><td>%.3f</td><td>%.3f</td><td>%.3f</td><td>%s</td></tr>\n' % (a_max - a_min, 0, slope_sd_tol, ok_dict[diff_ok]))
00394 html.append('</table>\n')
00395
00396 html.append('<p>Slope intercepts must be within tolerance of expected values, or the average effort is incorrect.</p>\n')
00397 html.append('<table border="1" cellpadding="2" cellspacing="0">\n')
00398 html.append('<tr><td><b>Name</b></td><td><b>Intercept</b></td><td><b>Expected</b><td><b>Tolerance</b></td><td><b>Passed</b></td>\n')
00399 html.append('<tr><td>Positive</td><td>%.3f</td><td>%.3f</td><td>%.3f</td><td>%s</td></tr>\n' % (b_max, params.pos_effort, tol_intercept, ok_dict[pos_int_ok]))
00400 html.append('<tr><td>Negative</td><td>%.3f</td><td>%.3f</td><td>%.3f</td><td>%s</td></tr>\n' % (b_min, params.neg_effort, tol_intercept, ok_dict[neg_int_ok]))
00401 html.append('</table>\n')
00402
00403 result.html = ''.join(html)
00404
00405 result.values.append(get_test_value('Slope Positive', a_max, params.slope - slope_sd_tol, params.slope + slope_sd_tol))
00406 result.values.append(get_test_value('Slope Negative', a_min, params.slope - slope_sd_tol, params.slope + slope_sd_tol))
00407 result.values.append(get_test_value('Intercept Positive', b_max, params.pos_effort - tol_intercept, params.pos_effort + tol_intercept))
00408 result.values.append(get_test_value('Intercept Negative', b_min, params.neg_effort - tol_intercept, params.neg_effort + tol_intercept))
00409
00410 return result
00411
00412
00413
00414 def plot_effort(params, data):
00415
00416 fig = plt.figure(1)
00417 axes1 = fig.add_subplot(211)
00418 axes2 = fig.add_subplot(212)
00419 axes2.set_xlabel('Position (Radians or Meters)')
00420 axes1.set_ylabel('Effort (Nm or N)')
00421 axes2.set_ylabel('Effort (Nm or N)')
00422 axes1.plot(data.positive.position, data.positive.effort, 'b--', label='_nolegend_')
00423 axes2.plot(data.negative.position, data.negative.effort, 'b--', label='_nolegend_')
00424
00425 max_avg = numpy.average(data.positive.effort)
00426 min_avg = numpy.average(data.negative.effort)
00427 max_sd = numpy.std(data.positive.effort)
00428 min_sd = numpy.std(data.negative.effort)
00429
00430 axes1.axhline(y = max_avg, color = 'r', label='Average')
00431 axes1.axhline(y = max_avg + max_sd, color = 'y', label='Error bars')
00432 axes1.axhline(y = max_avg - max_sd, color = 'y', label='_nolegend_')
00433
00434 axes2.axhline(y = min_avg, color = 'r', label='Average')
00435 axes2.axhline(y = min_avg - min_sd, color = 'y', label='Error bars')
00436 axes2.axhline(y = min_avg + min_sd, color = 'y', label='_nolegend_')
00437
00438
00439 axes1.axhline(y = params.pos_effort, color = 'g', label='Expected')
00440 axes2.axhline(y = params.neg_effort, color = 'g', label='Expected')
00441
00442 fig.text(.3, .95, params.joint_name + ' Hysteresis Efforts')
00443
00444
00445 stream = StringIO()
00446 plt.savefig(stream, format = "png")
00447 image = stream.getvalue()
00448 plt.close()
00449
00450 p = Plot()
00451 p.title = params.joint_name + "_hysteresis1"
00452 p.image = image
00453 p.image_format = "png"
00454
00455 return p
00456
00457
00458
00459 def plot_velocity(params, data):
00460 fig = plt.figure(2)
00461 plt.ylabel('Velocity')
00462 plt.xlabel('Position')
00463 plt.plot(numpy.array(data.positive.position), numpy.array(data.positive.velocity), 'b--', label='Data')
00464 plt.plot(numpy.array(data.negative.position), numpy.array(data.negative.velocity), 'b--', label='_nolegened_')
00465 plt.axhline(y = params.velocity, color = 'g', label = 'Command')
00466 plt.axhline(y = -1 * params.velocity, color = 'g', label = '_nolegend_')
00467
00468 fig.text(.3, .95, params.joint_name + ' Hysteresis Velocity')
00469 plt.legend(shadow=True)
00470
00471 stream = StringIO()
00472 plt.savefig(stream, format = "png")
00473 image = stream.getvalue()
00474
00475 p = Plot()
00476 p.title = params.joint_name + "_hysteresis2"
00477 p.image = image
00478 p.image_format = "png"
00479
00480 plt.close()
00481
00482 return p
00483
00484
00485
00486 class WristRollHysteresisTestData(HysteresisTestData):
00487 """Struct to hold wrist test data"""
00488 def __init__(self, msg):
00489 left_min = int(0.05 * len(msg.left_turn.roll_position))
00490 left_max = int(0.95 * len(msg.left_turn.roll_position))
00491 right_min = int(0.05 * len(msg.right_turn.roll_position))
00492 right_max = int(0.95 * len(msg.right_turn.roll_position))
00493
00494 self.pos_flex_effort = numpy.array(msg.left_turn.flex_effort) [left_min: left_max]
00495 self.neg_flex_effort = numpy.array(msg.right_turn.flex_effort)[right_min: right_max]
00496
00497 self.positive = HysteresisDirectionData(msg.left_turn.roll_position, msg.left_turn.roll_effort, msg.left_turn.roll_velocity)
00498 self.negative = HysteresisDirectionData(msg.right_turn.roll_position, msg.right_turn.roll_effort, msg.right_turn.roll_velocity)
00499
00500 class WristRollHysteresisParams(HysteresisParameters):
00501 """Wrist test parameters"""
00502 def __init__(self, msg):
00503 self.joint_name = msg.roll_joint
00504 self.p_gain = msg.roll_pid[0]
00505 self.i_gain = msg.roll_pid[1]
00506 self.d_gain = msg.roll_pid[2]
00507 self.i_clamp = msg.roll_pid[3]
00508
00509 self.velocity = msg.arg_value[1]
00510 self.tolerance = msg.arg_value[2]
00511 self.sd_max = msg.arg_value[3]
00512
00513 self.timeout = msg.arg_value[4]
00514 self.pos_effort = msg.arg_value[5]
00515 self.neg_effort = msg.arg_value[6]
00516
00517 self.range_max = 0
00518 self.range_min = 0
00519 self.slope = 0
00520
00521
00522 self.flex_joint = msg.flex_joint
00523 self.flex_tol = msg.arg_value[7]
00524 self.flex_max = msg.arg_value[8]
00525 self.flex_sd = msg.arg_value[9]
00526 self.flex_p_gain = msg.flex_pid[0]
00527 self.flex_i_gain = msg.flex_pid[1]
00528 self.flex_d_gain = msg.flex_pid[2]
00529 self.flex_i_clamp = msg.flex_pid[3]
00530
00531 def get_test_params(self):
00532 test_params = HysteresisParameters.get_test_params(self)
00533
00534 test_params.append(TestParam("Flex Joint", self.flex_joint))
00535 test_params.append(TestParam("Flex Tolerance", str(self.flex_tol)))
00536 test_params.append(TestParam("Flex Max", str(self.flex_max)))
00537 test_params.append(TestParam("Flex SD", str(self.flex_sd)))
00538 test_params.append(TestParam("Flex P Gain", str(self.flex_p_gain)))
00539 test_params.append(TestParam("Flex I Gain", str(self.flex_i_gain)))
00540 test_params.append(TestParam("Flex D Gain", str(self.flex_d_gain)))
00541 test_params.append(TestParam("Flex I Clamp", str(self.flex_i_clamp)))
00542
00543 return test_params
00544
00545
00546
00547
00548
00549
00550
00551
00552
00553
00554
00555
00556 def wrist_flex_analysis(params, data):
00557 flex_max = numpy.average(data.pos_flex_effort)
00558 flex_max_sd = numpy.std(data.pos_flex_effort)
00559 flex_min = numpy.average(data.neg_flex_effort)
00560 flex_min_sd = numpy.std(data.neg_flex_effort)
00561 flex_max_val = max(numpy.max(data.pos_flex_effort), numpy.max(data.neg_flex_effort))
00562 flex_min_val = min(numpy.min(data.pos_flex_effort), numpy.min(data.neg_flex_effort))
00563
00564 max_msg = '<div class="pass">OK</div>'
00565 if abs(flex_max) > params.flex_tol:
00566 max_msg = '<div class="error">FAIL</div>'
00567
00568 min_msg = '<div class="pass">OK</div>'
00569 if abs(flex_min) > params.flex_tol:
00570 min_msg = '<div class="error">FAIL</div>'
00571
00572 max_val_msg = '<div class="pass">OK</div>'
00573 if abs(flex_max_val) > params.flex_max:
00574 max_val_msg = '<div class="error">FAIL</div>'
00575
00576 min_val_msg = '<div class="pass">OK</div>'
00577 if abs(flex_min_val) > params.flex_max:
00578 min_val_msg = '<div class="error">FAIL</div>'
00579
00580 max_sd_msg = '<div class="pass">OK</div>'
00581 if abs(flex_max_sd) > params.flex_sd:
00582 max_sd_msg = '<div class="error">FAIL</div>'
00583
00584 min_sd_msg = '<div class="pass">OK</div>'
00585 if abs(flex_min_sd) > params.flex_sd:
00586 min_sd_msg = '<div class="error">FAIL</div>'
00587
00588 ok = abs(flex_max) < params.flex_tol and abs(flex_min) < params.flex_tol
00589 ok = ok and abs(flex_min_val) < params.flex_max and abs(flex_max_val) < params.flex_max
00590
00591 if ok:
00592 html = ['<p>Wrist flex effort is OK.</p>']
00593 else:
00594 html = ['<p>Wrist flex effort failed. Check graphs.</p>']
00595
00596 html.append('<p>Flex effort maximum values. Allowed maximum: %.2f</p>' % (params.flex_max))
00597 html.append('<table border="1" cellpadding="2" cellspacing="0">')
00598 html.append('<tr><td></td><td><b>Effort</b></td><td><b>Status</b></td></tr>')
00599 html.append('<tr><td><b>Max Value</b></td><td>%.2f</td><td>%s</td></tr>' % (flex_max_val, max_val_msg))
00600 html.append('<tr><td><b>Min Value</b></td><td>%.2f</td><td>%s</td></tr>' % (flex_min_val, min_val_msg))
00601 html.append('</table>')
00602
00603 html.append('<br>')
00604 html.append('<p>Flex effort average and noise, both directions. Allowed absolute average: %.2f. Allowed noise: %.2f</p>' % (params.flex_tol, params.flex_sd))
00605 html.append('<table border="1" cellpadding="2" cellspacing="0">')
00606 html.append('<tr><td><b>Effort Avg</b></td><td><b>Status</b></td><td><b>Effort SD</b></td><td><b>SD Status</b></td></tr>')
00607 html.append('<tr><td>%.2f</td><td>%s</td><td>%.2f</td><td>%s</td></tr>' % (flex_max, max_msg, flex_max_sd, max_sd_msg))
00608 html.append('<tr><td>%.2f</td><td>%s</td><td>%.2f</td><td>%s</td></tr>' % (flex_min, min_msg, flex_min_sd, min_sd_msg))
00609 html.append('</table>')
00610
00611 result = HysteresisAnalysisResult()
00612 result.html = '\n'.join(html)
00613 result.result = ok
00614
00615 result.values = [
00616 get_test_value('Flex Pos Average', flex_max, '', params.flex_tol),
00617 get_test_value('Flex Pos SD', flex_max_sd, '', params.flex_sd),
00618 get_test_value('Flex Neg Average', flex_min, '', params.flex_tol),
00619 get_test_value('Flex Neg SD', flex_min_sd, '', params.flex_sd),
00620 get_test_value('Flex Max Val', flex_max_val, '', params.flex_max),
00621 get_test_value('Flex Min Val', flex_min_val, '', -1 * params.flex_max)
00622 ]
00623
00624 return result
00625
00626
00627
00628 def plot_flex_effort(params, data):
00629
00630
00631 flex_max_tol = params.flex_max
00632
00633 fig = plt.figure(1)
00634 axes1 = fig.add_subplot(211)
00635 axes2 = fig.add_subplot(212)
00636 axes2.set_xlabel('Roll Position')
00637 axes1.set_ylabel('Effort (+ dir)')
00638 axes2.set_ylabel('Effort (- dir)')
00639
00640 axes1.plot(data.positive.position, data.pos_flex_effort, 'b--', label='_nolegend_')
00641 axes1.axhline(y = flex_max_tol, color = 'y', label='Max Value')
00642 axes1.axhline(y = - flex_max_tol, color = 'y', label='_nolegend_')
00643 axes1.axhline(y = 0, color = 'r', label='_nolegend_')
00644
00645 axes2.plot(data.negative.position, data.neg_flex_effort, 'b--', label='_nolegend_')
00646 axes2.axhline(y = flex_max_tol, color = 'y', label='Max Value')
00647 axes2.axhline(y = - flex_max_tol, color = 'y', label='_nolegend_')
00648 axes2.axhline(y = 0, color = 'r', label='_nolegend_')
00649
00650 fig.text(.4, .95, 'Wrist Flex Effort')
00651
00652 stream = StringIO()
00653 plt.savefig(stream, format = "png")
00654 image = stream.getvalue()
00655
00656 p = Plot()
00657 p.title = "wrist_diff_flex_effort"
00658 p.image = image
00659 p.image_format = "png"
00660
00661 plt.close()
00662
00663 return p
00664
00665
00666 def make_wrist_test_summary(roll_stat, flex_stat):
00667 if flex_stat and roll_stat:
00668 return "Wrist Difference check OK. Motors are symmetric."
00669 if flex_stat and not roll_stat:
00670 return "Wrist roll hysteresis failed. Wrist flex effort OK."
00671 if not flex_stat and roll_stat:
00672 return "Wrist roll hysteresis OK. Wrist flex effort failed."
00673 return "Wrist roll hystereis and flex effort failed."
00674
00675
00676
00677 def wrist_hysteresis_data_present(data):
00678 return data.positive.position.size > 100 and data.negative.position.size > 100