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
00035 roslib.load_manifest(PKG)
00036
00037 import rospy
00038 from time import sleep
00039
00040 import sys
00041
00042 from diagnostic_msgs.msg import DiagnosticArray
00043
00044 from pr2_self_test_msgs.srv import TestResult, TestResultRequest
00045 from pr2_self_test_msgs.srv import ScriptDone, ScriptDoneRequest, ScriptDoneResponse
00046
00047 from joint_qualification_controllers.msg import RobotData
00048 from std_msgs.msg import Bool
00049 from std_srvs.srv import Empty
00050
00051 import traceback
00052
00053 ETHERCAT_WAIT_TIME = 10
00054 OPERATOR_WAIT_TIME = 60
00055
00056
00057 def level_cmp(a, b):
00058 if a._level == b._level:
00059 return cmp(a._name, b._name)
00060
00061 return cmp(b._level, a._level)
00062
00063
00064 def _write_diag_summary(error_names, num_error, num_warn, num_stale):
00065 camera = False
00066 for name in error_names:
00067 if name.find('wge100') > 0:
00068 camera = True
00069
00070 if camera:
00071 return 'Error in wge100 camera. Check camera connection. '
00072
00073 hokuyo = False
00074 for name in error_names:
00075 if name.find('hokuyo') > 0:
00076 hokuyo = True
00077
00078 ethercat = error_names.count('EtherCAT Master') > 0
00079
00080 if ethercat:
00081 return 'EtherCAT error. Check runstop. Motors or MCB\'s may have problem. '
00082
00083 if hokuyo:
00084 return 'Hokuyo error. Check connections. '
00085
00086 return 'Diagnostics FAIL: %s errors, %s warnings, %s stale items. ' % (num_error, num_warn, num_stale)
00087
00088 class DiagnosticItem(object):
00089 def __init__(self, name, level, message):
00090 self._name = name
00091 self._level = level
00092 self._message = message
00093 self._update_time = rospy.get_time()
00094
00095 def discard(self):
00096 if self._name.startswith('Controller'):
00097 return True
00098
00099 if self._name == 'Realtime Control Loop':
00100 return True
00101
00102 return False
00103
00104 def check_stale(self):
00105 if rospy.get_time() - self._update_time > 3.0:
00106 self._level = 3
00107
00108 def update_item(self, level, message):
00109 self._update_time = rospy.get_time()
00110 self._level = level
00111 self._message = message
00112
00113
00114 class RobotCheckout(object):
00115 def __init__(self):
00116 rospy.init_node('robot_checkout')
00117
00118 self._calibrated = False
00119 self._joints_ok = False
00120
00121 self._has_robot_data = False
00122 self._has_visual_check = False
00123 self._visual_check_time = 0
00124
00125
00126 self._messages = []
00127 self._name_to_diagnostic = {}
00128
00129 self._joint_sum = 'No joint data. '
00130 self._act_sum = 'No actuator data. '
00131 self._joint_html = '<p>No joint data.</p><hr size="2">\n'
00132 self._act_html = '<p>No actuator data.</p><hr size="2">\n'
00133
00134 self._visual_sum = 'No visual check. '
00135 self._visual_html = '<p>No response from visual verification!</p>\n'
00136
00137 self._joints_ok = False
00138 self._acts_ok = False
00139 self._is_ok = False
00140 self._visual_ok = False
00141
00142 self._timeout = True
00143 self._check_time = 0
00144
00145 self.has_sent_result = False
00146
00147 self._expected_actuators = rospy.get_param('~motors', None)
00148
00149 self._has_reset = False
00150 self._motors_halted = True
00151 self._last_motors_time = 0
00152 self.motors_topic = rospy.Subscriber("pr2_etherCAT/motors_halted", Bool, self.on_motor_cb)
00153
00154 self.robot_data = rospy.Subscriber('robot_checkout', RobotData, self.on_robot_data)
00155 self.result_srv = rospy.ServiceProxy('test_result', TestResult)
00156
00157 self.diagnostics = rospy.Subscriber('diagnostics', DiagnosticArray, self.on_diagnostic_msg)
00158 self.visual_srv = rospy.Service('visual_check', ScriptDone, self.on_visual_check)
00159
00160 def _reset_motors(self):
00161 if self._has_reset:
00162 return
00163
00164 try:
00165 proxy = rospy.ServiceProxy('pr2_etherCAT/reset_motors', Empty)
00166 proxy()
00167 self._has_reset = True
00168 except Exception, e:
00169 pass
00170
00171 def on_motor_cb(self, msg):
00172 self._motors_halted = msg.data
00173 self._last_motors_time = rospy.get_time()
00174
00175 if self._motors_halted:
00176 self._reset_motors()
00177
00178 def send_failure_call(self, caller = 'No caller', except_str = ''):
00179 if self.has_sent_result:
00180 rospy.logerr('Wanted to send failure call after result sent. Caller: %s. Exception:\n%s' % (caller, except_str))
00181 return
00182
00183 r = TestResultRequest()
00184 r.html_result = '<p><b>Exception received during %s.</b></p>\n<p><b>Exception:</b> %s</p>\n' % (caller, except_str)
00185 r.text_summary = 'Exception during %s.' % caller
00186 r.plots = []
00187 r.result = r.RESULT_FAIL
00188 try:
00189 rospy.wait_for_service('test_result', 10)
00190 self.result_srv.call(r)
00191 self.has_sent_result = True
00192 except Exception, e:
00193 rospy.logerr('Caught exception sending failure call! %s' % traceback.format_exc())
00194 traceback.print_exc()
00195
00196 def _check_motors_stale(self):
00197 """
00198 Returns true if "motors_halted" topic hasn't updated in a while.
00199 """
00200 return self._last_motors_time == 0 or rospy.get_time() - self._last_motors_time > ETHERCAT_WAIT_TIME
00201
00202 def wait_for_data(self):
00203 try:
00204 rospy.logdebug('Robot checkout is waiting for diagnostics')
00205
00206 for i in range(0, 20):
00207 if not rospy.is_shutdown():
00208 sleep(0.5)
00209
00210
00211 if self._check_motors_stale():
00212 self.checkout_robot()
00213 return
00214
00215 rospy.logdebug('Waiting for robot checkout controller')
00216
00217 while not rospy.is_shutdown():
00218
00219 if self._check_motors_stale():
00220 self.checkout_robot()
00221 return
00222
00223
00224 if self._has_visual_check and not self._visual_ok:
00225 self.checkout_robot()
00226 return
00227
00228
00229 if self._has_visual_check and \
00230 (rospy.get_time() - self._visual_check_time) > OPERATOR_WAIT_TIME:
00231 self.checkout_robot()
00232 return
00233
00234
00235 if self._has_robot_data and self._has_visual_check:
00236 self.checkout_robot()
00237 return
00238 sleep(0.5)
00239
00240 except KeyboardInterrupt:
00241 pass
00242 except Exception, e:
00243 self.send_failure_call('wait_for_data', traceback.format_exc())
00244
00245 def on_diagnostic_msg(self, message):
00246 try:
00247 for stat in message.status:
00248 if stat.name not in self._name_to_diagnostic:
00249 self._name_to_diagnostic[stat.name] = DiagnosticItem(stat.name, stat.level, stat.message)
00250
00251 else:
00252 self._name_to_diagnostic[stat.name].update_item(stat.level, stat.message)
00253 except Exception, e:
00254 rospy.logerr('Caught exception processing diagnostic msg.\nEx: %s' % traceback.format_exc())
00255 self.send_failure_call('on_diagnostic_msg', traceback.format_exc())
00256
00257 def on_visual_check(self, srv):
00258 rospy.logdebug('Got visual check')
00259 self._has_visual_check = True
00260 self._visual_check_time = rospy.get_time()
00261
00262 if srv.result == ScriptDoneRequest.RESULT_OK:
00263 self._visual_ok = True
00264 self._visual_sum = 'Visual: OK. '
00265 self._visual_html = '<p>Visual Verification Succeeded.</p>\n'
00266 else:
00267 self._visual_ok = False
00268 self._visual_html = '<p>Visual Verification Failed. '
00269 if srv.result == ScriptDoneRequest.RESULT_FAIL:
00270 self._visual_sum = 'Visual: FAIL. '
00271 self._visual_html += 'Operator recorded failure. Message: %s</p>\n' % srv.failure_msg
00272 else:
00273 self._visual_sum = 'Visual: ERROR. '
00274 self._visual_html += 'Visual verifier reported error!</p>\n'
00275 self._visual_html += '<p>Failure data:<br>%s</p>\n' % srv.failure_msg
00276
00277 return ScriptDoneResponse()
00278
00279
00280
00281 def on_robot_data(self, msg):
00282 rospy.logdebug('Got robot data service')
00283 self._has_robot_data = True
00284
00285 self._timeout = msg.timeout
00286
00287 self._check_time = msg.test_time
00288 self.joint_data(msg.joint_data)
00289 self.act_data(msg.actuator_data)
00290
00291
00292 def process_diagnostics(self):
00293
00294 my_diags = dict.values(self._name_to_diagnostic)
00295
00296 diagnostics = []
00297 for diag in my_diags:
00298 if diag.discard():
00299 continue
00300
00301 diag.check_stale()
00302 diagnostics.append(diag)
00303
00304 diagnostics.sort(level_cmp)
00305
00306
00307 stat_count = { 3: 0, 0: 0, 1: 0, 2: 0}
00308
00309 level_dict = { 3: 'Stale', 0: 'OK', 1: 'Warn', 2: 'Error' }
00310
00311 table = '<table border=\"1\" cellpadding=\"2\" cellspacing=\"0\">\n'
00312 table += '<tr><td><b>Name</b></td><td><b>Level</b></td><td><b>Message</b></td></tr>\n'
00313
00314 error_names = []
00315
00316 for diag in diagnostics:
00317 level = level_dict[diag._level]
00318 table += '<tr><td>%s</td><td>%s</td><td>%s</td></tr>\n' % (diag._name, level, diag._message)
00319 stat_count[diag._level] = stat_count[diag._level] + 1
00320
00321 if diag._level > 0:
00322 error_names.append(diag._name)
00323
00324 table += '</table>\n'
00325
00326 if stat_count[2] == 0 and stat_count[1] == 0 and stat_count[3] == 0 and len(diagnostics) > 0:
00327 summary = 'Diagnostics: OK. '
00328 self._is_ok = True
00329 else:
00330 if len(diagnostics) == 0:
00331 summary = 'No diagnostics received! '
00332 self._is_ok = False
00333 else:
00334 summary = _write_diag_summary(error_names, stat_count[2], stat_count[1], stat_count[3])
00335 self._is_ok = False
00336
00337 html = '<p><b>Diagnostic Data</b></p><p>%s</p><br>\n' % summary
00338 html += table
00339
00340 return summary, html
00341
00342 def checkout_robot(self):
00343 if self.has_sent_result:
00344 return
00345
00346 try:
00347 html = '<p><b>Robot Checkout Test</b></p><br>\n'
00348
00349 diag_sum, diag_html = self.process_diagnostics()
00350 summary = ''
00351
00352 if not self._has_robot_data:
00353 summary += 'No robot data received! '
00354 html += '<p><b>No robot data received!</b> CheckoutController might have had an error.</p>\n'
00355
00356 if self._timeout and self._has_robot_data:
00357 summary += 'Test timed out. '
00358 html += '<p><b>Timeout in robot checkout controller! Check Time: %2f</b></p>\n' % self._check_time
00359 else:
00360 html += '<p>Time to complete check: %.3fs.</p>\n' % self._check_time
00361
00362 if not self._is_ok:
00363 if not self._joints_ok:
00364 summary += 'Joints not OK. Check calibration status'
00365 else:
00366 summary += diag_sum
00367 else:
00368 summary += 'Data: ' + diag_sum + self._visual_sum + self._joint_sum + self._act_sum
00369
00370 if self._motors_halted:
00371 html += "<p>Motors halted, robot is not working.</p>\n"
00372 summary = "Motors halted. Check runstop. " + summary
00373
00374 if self._check_motors_stale():
00375 html += '<p>No recent updates from pr2_etherCAT. pr2_etherCAT may have crashed.</p>'
00376 summary = "No updates from pr2_etherCAT. May have crashed. Check MCB's, cable and power."
00377
00378
00379 html += diag_html + '<hr size="2">\n'
00380 html += self._visual_html + '<hr size="2">\n'
00381 html += self._joint_html + '<hr size="2">\n'
00382 html += self._act_html + '<hr size="2">\n'
00383
00384
00385 r = TestResultRequest()
00386 r.html_result = html
00387 r.text_summary = summary
00388
00389 if self._is_ok and self._visual_ok and self._joints_ok and \
00390 self._acts_ok and not self._timeout and not self._motors_halted:
00391 r.result = r.RESULT_PASS
00392 else:
00393 r.result = r.RESULT_FAIL
00394
00395 rospy.wait_for_service('test_result', 5)
00396
00397 try:
00398 self.result_srv.call(r)
00399 self.has_sent_result = True
00400 except Exception, e:
00401 rospy.logerr('Caught exception sending OK service. %s' % traceback.format_exc())
00402 except Exception, e:
00403 self.send_failure_call('checkout_robot', traceback.format_exc())
00404
00405 def act_data(self, act_datas):
00406 try:
00407 self._acts_ok = True
00408
00409 found_acts = []
00410
00411 html = ['<p><b>Actuator Data</b></p><br>\n']
00412 html.append('<table border=\"1\" cellpadding=\"2\" cellspacing=\"0\">\n')
00413 html.append('<tr><td><b>Index</b></td><td><b>Name</b></td><td><b>ID</b></td><td><b>Expected</b></td></tr>\n')
00414 for act_data in act_datas:
00415 index = act_data.index
00416 name = act_data.name
00417 id = act_data.id
00418
00419 expect = 'N/A'
00420 found_acts.append(act_data.name)
00421
00422 expect = 'True'
00423 if not self._expected_actuators or not act_data.name in self._expected_actuators:
00424 expect = 'False'
00425 self._acts_ok = False
00426
00427 html.append('<tr><td>%d</td><td>%s</td><td>%d</td><td>%s</td></tr>\n' % (index, name, id, expect))
00428
00429
00430 if self._expected_actuators is not None:
00431 for name in self._expected_actuators:
00432 if not name in found_acts:
00433 html.append('<tr><td>N/A</td><td>%s</td><td>Not Found</td><td>True</td></tr>\n' % (name))
00434 self._acts_ok = False
00435 else:
00436 html.append('<tr><td>No Actuators Expected</td><td>Uh oh!</td><td>Not Found</td><td>True</td></tr>\n')
00437 self._acts_ok = False
00438
00439 html.append('</table>\n')
00440
00441 if self._acts_ok:
00442 self._act_sum = 'Acutators: OK. '
00443 else:
00444 self._act_sum = 'Actuators: FAIL! '
00445
00446 self._act_html = ''.join(html)
00447
00448 except Exception, e:
00449 self.send_failure_call('actuator_data', traceback.format_exc())
00450
00451
00452 def joint_data(self, jnt_datas):
00453
00454 try:
00455 self._joints_ok = True
00456 self._calibrated = True
00457
00458 html = '<table border=\"1\" cellpadding=\"2\" cellspacing=\"0\">\n'
00459 html += '<tr><td><b>Index</b></td><td><b>Name</b></td><td><b>Type</b></td><td><b>Is Cal?</b></td><td><b>Has Safety?</b></td></tr>\n'
00460 for jnt_data in jnt_datas:
00461 id = jnt_data.index
00462 name = jnt_data.name
00463 type = jnt_data.type
00464
00465 if jnt_data.is_cal == 1:
00466 cal = '<div class=\"pass\">OK</div>'
00467 elif name.endswith('wheel_joint'):
00468 cal = '<div class=\"pass\">Wheel</div>'
00469 elif name == 'base_joint':
00470 cal = '<div class=\"pass\">Base</div>'
00471 elif name.find('finger') > 0:
00472 cal = '<div class=\"pass\">Gripper</div>'
00473 elif name.find('accelerometer') > 0:
00474 cal = '<div class=\"pass\">Gripper</div>'
00475 elif name.find('gripper_float_joint') > 0:
00476 cal = '<div class=\"pass\">Gripper</div>'
00477 elif name.find('gripper_palm_joint') > 0:
00478 cal = '<div class=\"pass\">Gripper</div>'
00479 elif name.find('gripper_tool_joint') > 0:
00480 cal = '<div class=\"pass\">Gripper</div>'
00481 else:
00482 cal = '<div class=\"warn\"><b>NO</b></div>'
00483 self._joints_ok = False
00484 self._calibrated = False
00485
00486 if jnt_data.has_safety:
00487 safe = 'OK'
00488 elif type == 'Continuous':
00489
00490 safe = '<div class=\"pass\">Continuous</div>'
00491 elif type == 'Fixed':
00492 safe = '<div class=\"pass\">Fixed</div>'
00493 elif type =='Planar' and name=='base_joint':
00494 safe = '<div class=\"pass\">Base Joint</div>'
00495 elif jnt_data.name.find('finger') > 0:
00496 safe == '<div class=\"pass\">Finger Joint</div>'
00497 else:
00498 safe = '<div class=\"warn\">NO</div>'
00499 self._joints_ok = False
00500
00501 html += '<tr><td>%d</td><td>%s</td><td>%s</td><td>%s</td><td>%s</td></tr>\n' % (id, name, type, cal, safe)
00502
00503 html += '</table>\n'
00504
00505 if self._joints_ok:
00506 self._joint_sum = 'Joint states: OK. '
00507 else:
00508 if self._calibrated:
00509 self._joint_sum = 'Joint states: FAIL. '
00510 else:
00511 self._joint_sum = 'Joints states: FAIL, not all calibrated. '
00512 self._joint_html = '<p><b>Joint Data</b></p><p>%s</p><br>\n' % self._joint_sum
00513 self._joint_html += html
00514 except Exception, e:
00515 self.send_failure_call('joint_data', traceback.format_exc())
00516
00517
00518 if __name__ == '__main__':
00519 try:
00520 checkout = RobotCheckout()
00521 sleep(1)
00522 checkout.wait_for_data()
00523 rospy.spin()
00524 except KeyboardInterrupt:
00525 pass
00526 except Exception, e:
00527 print 'Caught exception in robot checkout.\n%s' % traceback.format_exc()
00528 rospy.logerr('Robot checkout exception.\n%s' % traceback.format_exc())
00529