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 PKG = 'qualification'
00039
00040 import roslib
00041 roslib.load_manifest(PKG)
00042
00043 import rospy
00044
00045 import os
00046 import sys
00047 import threading
00048
00049 from datetime import datetime
00050 import wx
00051 import time
00052 from wx import xrc
00053 from wx import html
00054
00055 from xml.dom import minidom
00056
00057 from pr2_self_test_msgs.srv import ScriptDone, ScriptDoneRequest, ScriptDoneResponse
00058 from pr2_self_test_msgs.srv import TestResult, TestResultRequest, TestResultResponse
00059
00060 from qualification.test import *
00061 from qualification.result import *
00062 import cont_frame
00063
00064 import traceback
00065
00066 from wg_invent_client import Invent
00067 from runtime_monitor.monitor_panel import MonitorPanel
00068 from roslaunch_caller import roslaunch_caller
00069
00070 import rxtools.cppwidgets
00071
00072
00073
00074
00075 class QualTestObject(object):
00076 def __init__(self, name, serial):
00077 self.name = name
00078 self.serial = serial
00079
00080 class QualOptions(object):
00081 def __init__(self):
00082 self.debug = False
00083 self.always_show_results = False
00084 self.continuous = False
00085
00086
00087 class InstructionsPanel(wx.Panel):
00088 def __init__(self, parent, resource, qualification_frame, file):
00089 wx.Panel.__init__(self, parent)
00090
00091 self._manager = qualification_frame
00092
00093 self._panel = resource.LoadPanel(self, 'instructions_panel')
00094 self._sizer = wx.BoxSizer(wx.HORIZONTAL)
00095
00096 self._html_window = xrc.XRCCTRL(self._panel, 'html_window')
00097 self._continue_button = xrc.XRCCTRL(self._panel, 'continue_button')
00098 self._html_window.LoadFile(file)
00099
00100 self._continue_button.Bind(wx.EVT_BUTTON, self.on_continue)
00101 self._continue_button.SetFocus()
00102
00103 self._sizer.Add(self._panel, 1, wx.EXPAND|wx.ALIGN_CENTER_VERTICAL)
00104 self.SetSizer(self._sizer)
00105 self.Layout()
00106 self.Fit()
00107
00108 self._cancel_button = xrc.XRCCTRL(self._panel, 'cancel_button')
00109 self._cancel_button.Bind(wx.EVT_BUTTON, self.on_cancel)
00110
00111 def on_continue(self, event):
00112 self._manager.start_qualification()
00113
00114 def on_cancel(self, event):
00115
00116 self._manager.reset()
00117
00118
00119
00120
00121
00122 class PlotsPanel(wx.Panel):
00123 def __init__(self, parent, resource, qualification_frame):
00124 wx.Panel.__init__(self, parent)
00125
00126 self._manager = qualification_frame
00127
00128 self._panel = resource.LoadPanel(self, 'plots_panel')
00129 self._sizer = wx.BoxSizer(wx.HORIZONTAL)
00130
00131 self._sizer.Add(self._panel, 1, wx.EXPAND)
00132 self.SetSizer(self._sizer)
00133 self.Layout()
00134
00135 self._plots_window = xrc.XRCCTRL(self._panel, 'plots_window')
00136 self._pass_button = xrc.XRCCTRL(self._panel, 'pass_button')
00137 self._fail_button = xrc.XRCCTRL(self._panel, 'fail_button')
00138 self._retry_button = xrc.XRCCTRL(self._panel, 'retry_button')
00139
00140 self._pass_button.Bind(wx.EVT_BUTTON, self.on_pass)
00141 self._fail_button.Bind(wx.EVT_BUTTON, self.on_fail)
00142 self._retry_button.Bind(wx.EVT_BUTTON, self.on_retry)
00143
00144 self._notes_text = xrc.XRCCTRL(self._panel, 'notes_text')
00145
00146 self._cancel_button = xrc.XRCCTRL(self._panel, 'cancel_button')
00147 self._cancel_button.Bind(wx.EVT_BUTTON, self.on_cancel)
00148
00149
00150 self._notebook = xrc.XRCCTRL(self._panel, 'results_notebook')
00151 self._create_monitor()
00152 self._create_rxconsole()
00153
00154 def _create_monitor(self):
00155 self._monitor_panel = MonitorPanel(self._notebook)
00156 self._monitor_panel.SetSize(wx.Size(400, 500))
00157 self._notebook.AddPage(self._monitor_panel, "Diagnostics")
00158
00159 def _create_rxconsole(self):
00160 rxtools.cppwidgets.initRoscpp("qualification_console", True)
00161
00162 self._rxconsole_panel = rxtools.cppwidgets.RosoutPanel(self._notebook)
00163 self._rxconsole_panel.SetSize(wx.Size(400, 500))
00164 self._rxconsole_panel.setEnabled(True)
00165 self._notebook.AddPage(self._rxconsole_panel, "ROS Output")
00166
00167 def close(self):
00168 self._monitor_panel.shutdown()
00169
00170
00171
00172
00173
00174
00175 def show_plots(self, result_page, pass_ok):
00176 self._notes_text.SetEditable(True)
00177 self._notebook.SetSelection(0)
00178 self._plots_window.SetPage(result_page)
00179
00180
00181 self._pass_button.Enable(pass_ok)
00182
00183 self._fail_button.Enable(True)
00184 self._retry_button.Enable(True)
00185 self._cancel_button.Enable(True)
00186 self._pass_button.SetFocus()
00187
00188 def show_waiting(self, wait_page, cancel_enabled = True):
00189 self._notes_text.SetEditable(False)
00190 self._plots_window.SetPage(wait_page)
00191 self._pass_button.Enable(False)
00192 self._fail_button.Enable(False)
00193 self._retry_button.Enable(False)
00194 self._cancel_button.Enable(cancel_enabled)
00195
00196 def on_pass(self, event):
00197 notes = self._notes_text.GetValue()
00198 self._notes_text.Clear()
00199 self._manager.subtest_result(True, notes)
00200
00201 def on_fail(self, event):
00202 notes = self._notes_text.GetValue()
00203 self._notes_text.Clear()
00204 self._manager.subtest_result(False, notes)
00205
00206 def on_retry(self, event):
00207 notes = self._notes_text.GetValue()
00208 self._manager.retry_subtest(notes)
00209 self._notes_text.Clear()
00210
00211 def on_cancel(self, event):
00212 self._manager.cancel()
00213
00214
00215
00216
00217
00218 class ResultsPanel(wx.Panel):
00219 def __init__(self, parent, resource, qualification_frame):
00220 wx.Panel.__init__(self, parent)
00221
00222 self._manager = qualification_frame
00223
00224 self._panel = resource.LoadPanel(self, 'results_panel')
00225 self._sizer = wx.BoxSizer(wx.HORIZONTAL)
00226
00227 self._sizer.Add(self._panel, 1, wx.EXPAND|wx.ALIGN_CENTER_VERTICAL)
00228 self.SetSizer(self._sizer)
00229 self.Layout()
00230 self.Fit()
00231
00232 self._submit_button = xrc.XRCCTRL(self._panel, 'submit_button')
00233 self._results_window = xrc.XRCCTRL(self._panel, 'results_window')
00234
00235 self._notesbox = xrc.XRCCTRL(self._panel, 'notes_text')
00236 self._submit_button.Bind(wx.EVT_BUTTON, self.on_submit)
00237 self._submit_button.SetFocus()
00238
00239 self._dir_picker = xrc.XRCCTRL(self._panel, 'results_dir_picker')
00240
00241 def set_results(self, results):
00242 self._results_window.Freeze()
00243 self._results_window.SetPage(results.make_summary_page())
00244 self._results_window.Thaw()
00245 self._dir_picker.SetPath(results.results_dir)
00246
00247 def on_submit(self, event):
00248 self._manager.submit_results(self._notesbox.GetValue(), self._dir_picker.GetPath())
00249
00250
00251 def script_timeout(timeout):
00252 if timeout > 0:
00253 msg = 'Automated timeout. Timeout: %s' % timeout
00254 else:
00255 msg = 'Subtest aborted'
00256
00257 return ScriptDoneRequest(1, msg)
00258
00259
00260 def subtest_timeout(timeout):
00261 if timeout > 0:
00262 msg = 'Automated timeout. Timeout: %s' % timeout
00263 else:
00264 msg = 'Subtest aborted'
00265
00266 result = TestResultRequest()
00267 result.html_result = '<p>%s</p>\n' % msg
00268 result.text_summary = msg
00269 result.plots = []
00270 result.result = TestResultRequest.RESULT_FAIL
00271
00272 return result
00273
00274
00275 def make_html_waiting_page(subtest_name, index, len_subtests):
00276 html = ['<html><H2 align=center>Waiting for Subtest to Complete</H2>']
00277 html.append('<H3 align=center>Test Name: %s</H3>' % subtest_name)
00278 html.append('<H4 align=center>Test %d of %d</H4></html>' % (index + 1, len_subtests))
00279
00280 return '\n'.join(html)
00281
00282
00283
00284
00285 class QualificationFrame(wx.Frame):
00286 def __init__(self, parent, options):
00287 wx.Frame.__init__(self, parent, wx.ID_ANY, "Qualification")
00288
00289 self.options = options
00290
00291 self._result_service = None
00292 self._prestartup_done_srv = None
00293 self._shutdown_done_srv = None
00294
00295 self._invent_client = None
00296
00297
00298 xrc_path = os.path.join(roslib.packages.get_pkg_dir('qualification'), 'xrc/gui.xrc')
00299 self._res = xrc.XmlResource(xrc_path)
00300
00301
00302 self._root_panel = self._res.LoadPanel(self, 'main_panel')
00303
00304 self._top_panel = xrc.XRCCTRL(self._root_panel, "top_panel")
00305 self._top_sizer = wx.BoxSizer(wx.HORIZONTAL)
00306 self._top_panel.SetSizer(self._top_sizer)
00307 self._current_panel = None
00308 self._plots_panel = None
00309
00310 self._log_panel = xrc.XRCCTRL(self._root_panel, "log_panel")
00311 self._log = xrc.XRCCTRL(self._log_panel, 'log')
00312
00313 self._results = None
00314 self._cont_frame = None
00315
00316 self._startup_launch = None
00317 self._shutdown_launch = None
00318 self._subtest_launch = None
00319 self._prestartup_launch = None
00320 self._record_launch = None
00321
00322
00323 self._prestartup_done_srv = None
00324 self._result_service = None
00325 self._shutdown_done_srv = None
00326
00327
00328 self._prestart_timer = None
00329 self._subtest_timer = None
00330 self._shutdown_timer = None
00331
00332 self._current_test = None
00333
00334 rospy.set_param('/invent/username', '')
00335 rospy.set_param('/invent/password', '')
00336
00337 self._waiting_for_submit = False
00338
00339 self.Bind(wx.EVT_CLOSE, self.on_close)
00340
00341 self._spin_timer = wx.Timer(self, wx.ID_ANY)
00342 self.Bind(wx.EVT_TIMER, self.on_spin, self._spin_timer)
00343 self._spin_timer.Start(100)
00344
00345 self.log("Startup")
00346 self.reset()
00347
00348
00349 def log(self, msg):
00350 log_msg = datetime.now().strftime("%m/%d/%Y %H:%M:%S: ") + msg
00351 if self._results:
00352 self._results.log(msg)
00353 self._log.AppendText(log_msg + '\n')
00354 self._log.Refresh()
00355 self._log.Update()
00356
00357
00358 def set_top_panel(self, panel):
00359 if self._current_panel == panel:
00360 return
00361
00362 self._current_panel = panel
00363 self._top_sizer.Clear(True)
00364 self._top_sizer.Add(self._current_panel, 1, wx.EXPAND|wx.ALIGN_CENTER_VERTICAL)
00365 self._top_panel.Layout()
00366
00367
00368 def reset(self):
00369
00370 loader_panel = self.get_loader_panel()
00371 self.set_top_panel(loader_panel)
00372 if self._results:
00373 self._results.close()
00374 self._results = None
00375
00376 if self._plots_panel:
00377 self._plots_panel.close()
00378 self._plots_panel = None
00379
00380 self._current_test = None
00381 self._subtest_index = 0
00382
00383 self.reset_params()
00384
00385
00386 def reset_params(self):
00387 run_id = rospy.get_param('/run_id')
00388 roslaunch_params = rospy.get_param('/roslaunch', '')
00389 qual_params = rospy.get_param('/qualification', '')
00390 invent_params = rospy.get_param('/invent', '')
00391
00392 rospy.set_param('/', {'run_id': run_id,
00393 'roslaunch' : roslaunch_params,
00394 'qualification' : qual_params,
00395 'invent' : invent_params})
00396
00397
00398
00399
00400 def begin_test(self, test, qual_item):
00401
00402 if not self.get_inventory_object():
00403 wx.MessageBox('Cannot proceed without inventory login. You must have an inventory username and password.', 'Inventory Login Required', wx.OK|wx.ICON_ERROR, self)
00404 self.reset()
00405 return
00406
00407 self._current_test = test
00408 self._current_item = qual_item
00409
00410 rospy.set_param('/qual_item/serial', self._current_item.serial)
00411 rospy.set_param('/qual_item/name', self._current_item.name)
00412
00413 if (self._current_test.getInstructionsFile()) and not self.options.continuous:
00414 self.set_top_panel(InstructionsPanel(self._top_panel, self._res, self, self._current_test.getInstructionsFile()))
00415 else:
00416 self.start_qualification()
00417
00418
00419 def start_qualification(self):
00420 if (len(self._current_test.subtests) == 0):
00421 wx.MessageBox('Test selected has no subtests defined', 'No tests', wx.OK|wx.ICON_ERROR, self)
00422 return
00423
00424 self.record_tests()
00425
00426 self._tests_start_date = datetime.now()
00427
00428 self._results = QualTestResult(self._current_item, self._current_test, self._tests_start_date)
00429
00430
00431 self._plots_panel = PlotsPanel(self._top_panel, self._res, self)
00432
00433 self.run_prestartup_scripts()
00434
00435
00436 def record_tests(self):
00437
00438 record = '<launch>\n'
00439 record += '<node pkg="rosrecord" type="rosrecord" name="test_logger" \n'
00440 record += 'args="-f /hwlog/%s_qual_test /diagnostics" />\n' % self._current_item.serial
00441 record += '</launch>\n'
00442
00443 self._record_launch = self.launch_script(record)
00444 if (self._record_launch == None):
00445 rospy.logerr('Couldn\'t launch rosrecord for qualification test')
00446 return
00447
00448
00449 def run_prestartup_scripts(self):
00450 if (len(self._current_test.pre_startup_scripts) == 0):
00451 self.log('No prestartup scripts.')
00452 self.test_startup()
00453 return
00454
00455 self._prestartup_index = 0
00456
00457 if (self._prestartup_done_srv != None):
00458 self._prestartup_done_srv.shutdown()
00459 self._prestartup_done_srv = None
00460
00461 self.log('Running prestartup scripts')
00462
00463 self.prestartup_call()
00464
00465
00466 def prestartup_call(self):
00467 prestart = self._current_test.pre_startup_scripts[self._prestartup_index]
00468
00469 script = prestart.launch_file
00470 name = prestart.get_name()
00471
00472
00473 log_message = 'Running pre_startup script [%s]...'%(name)
00474 self.log(log_message)
00475
00476 wait_html = '<html><H2 align=center>Prestartup Scripts Running</H2>\n'
00477 wait_html += '<H3 align=center>Script: %s</H3>\n</html>' % name
00478
00479 self._plots_panel.show_waiting(wait_html)
00480
00481 self.set_top_panel(self._plots_panel)
00482
00483 self._prestartup_done_srv = rospy.Service('prestartup_done', ScriptDone, self.prestartup_done_callback)
00484
00485 self._prestartup_launch = self.launch_file(script)
00486 if (self._prestartup_launch == None):
00487 s = 'Could not load roslaunch script "%s"! Press OK to cancel test.' % (os.path.basename(script))
00488 wx.MessageBox(s, 'Invalid roslaunch file', wx.OK|wx.ICON_ERROR, self)
00489 self.cancel(s)
00490 return
00491
00492
00493 if prestart.get_timeout() > 0:
00494 timeout = prestart.get_timeout()
00495 self._prestart_timer = threading.Timer(timeout,
00496 self.prestartup_done_callback,
00497 [script_timeout(timeout)])
00498 self._prestart_timer.start()
00499
00500
00501 def prestartup_done_callback(self, srv):
00502 wx.CallAfter(self.prestartup_finished, srv)
00503 return ScriptDoneResponse()
00504
00505
00506
00507 def prestartup_finished(self, srv):
00508 if self._prestartup_done_srv:
00509 self._prestartup_done_srv.shutdown()
00510 self._prestartup_done_srv = None
00511
00512 if self._prestartup_launch != None:
00513 self._prestartup_launch.shutdown()
00514 self._prestartup_launch = None
00515
00516 if self._prestart_timer:
00517 self._prestart_timer.cancel()
00518 self._prestart_timer = None
00519
00520 result_dict = { 0: 'OK', 1: 'FAIL', 2: 'ERROR' }
00521 self.log('Prestartup script finished. Result %s.' % (result_dict[srv.result]))
00522
00523 self._results.add_prestartup_result(self._prestartup_index, srv)
00524
00525 if srv.result == 0:
00526
00527 self._prestartup_index += 1
00528 if self._prestartup_index >= len(self._current_test.pre_startup_scripts):
00529 self.test_startup()
00530 else:
00531 self.prestartup_call()
00532 else:
00533 self.test_finished()
00534
00535
00536 def test_startup(self):
00537
00538 startup = self._current_test.getStartupScript()
00539
00540 if startup:
00541 self.log('Running startup script...')
00542 self._startup_launch = self.launch_file(startup.launch_file)
00543 if (self._startup_launch == None):
00544 s = 'Could not load roslaunch script %s, file: "%s"' % (startup.get_name(), os.path.basename(startup.launch_file))
00545 wx.MessageBox(s, 'Invalid roslaunch file. Press OK to cancel.', wx.OK|wx.ICON_ERROR, self)
00546 self.cancel(s)
00547 return
00548
00549 rospy.sleep(2.0)
00550 rospy.loginfo('Sleeping after startup script')
00551
00552 else:
00553 self.log('No startup script, launching subtests')
00554
00555 self.start_subtest(0)
00556
00557
00558
00559 def start_subtest(self, index):
00560 self._subtest_index = index
00561
00562 subtest = self._current_test.subtests[self._subtest_index]
00563
00564 self._plots_panel.show_waiting(make_html_waiting_page(subtest.get_name(), index, len(self._current_test.subtests)))
00565 self.set_top_panel(self._plots_panel)
00566
00567 self.launch_pre_subtest()
00568
00569 self._result_service = rospy.Service('test_result', TestResult, self.subtest_callback)
00570
00571 script = subtest._test_script
00572 self._subtest_launch = self.launch_file(script)
00573 if (self._subtest_launch == None):
00574 s = 'Could not load roslaunch script "%s"'%(os.path.basename(script))
00575 wx.MessageBox(s, 'Invalid roslaunch file. Press OK to cancel.', wx.OK|wx.ICON_ERROR, self)
00576 self.cancel(s)
00577 return
00578
00579
00580 if subtest.get_timeout() > 0:
00581 timeout = subtest.get_timeout()
00582 self._subtest_timer = threading.Timer(timeout,
00583 self.subtest_callback,
00584 [ subtest_timeout(timeout) ])
00585 self._subtest_timer.start()
00586
00587
00588
00589 def subtest_callback(self, msg):
00590 wx.CallAfter(self.subtest_finished, msg)
00591 return TestResultResponse()
00592
00593
00594
00595
00596 def subtest_finished(self, msg):
00597 self._subtest_launch.shutdown()
00598 self._subtest_launch = None
00599
00600
00601 if self._result_service:
00602 self._result_service.shutdown()
00603 self._result_service = None
00604
00605 if self._subtest_timer:
00606 self._subtest_timer.cancel()
00607 self._subtest_timer = None
00608
00609 sub_result = self._results.add_sub_result(self._subtest_index, msg)
00610
00611 if self.options.continuous:
00612 if (msg.result == TestResultRequest.RESULT_PASS):
00613 self.subtest_result(True, '')
00614 elif self._cont_frame.pause_on_fail:
00615 self.show_plots(sub_result)
00616 else:
00617 self.subtest_result(False, '')
00618 elif self.options.always_show_results:
00619 self.show_plots(sub_result)
00620 else:
00621 if (msg.result == TestResultRequest.RESULT_PASS):
00622 self.subtest_result(True, '')
00623 elif (msg.result == TestResultRequest.RESULT_FAIL):
00624 self.subtest_result(False, '')
00625 elif (msg.result == TestResultRequest.RESULT_HUMAN_REQUIRED):
00626 self.log('Subtest "%s" needs human response.'%(self._current_test.subtests[self._subtest_index].get_name()))
00627 self.show_plots(sub_result)
00628
00629
00630 def show_plots(self, sub_result):
00631 self._plots_panel.show_plots(sub_result.make_result_page(),
00632 sub_result.get_pass_bool() or self.options.debug)
00633 self.set_top_panel(self._plots_panel)
00634
00635
00636
00637
00638 def subtest_result(self, pass_bool, operator_notes = ''):
00639 self.log('Subtest "%s" result: %s'%(self._current_test.subtests[self._subtest_index].get_name(), pass_bool))
00640
00641 sub_result = self._results.get_subresult(self._subtest_index)
00642 sub_result.set_note(operator_notes)
00643 sub_result.set_operator_result(pass_bool)
00644
00645 if pass_bool:
00646 self.launch_post_subtest()
00647 self.next_subtest()
00648 else:
00649 self.test_finished()
00650
00651
00652 def retry_subtest(self, notes):
00653 self.log('Retrying subtest "%s"'%(self._current_test.subtests[self._subtest_index].get_name()))
00654 self._results.retry_subresult(self._subtest_index, notes)
00655 self.start_subtest(self._subtest_index)
00656
00657
00658 def next_subtest(self):
00659 if (self._subtest_index + 1 >= len(self._current_test.subtests)):
00660 self.test_finished()
00661 else:
00662 self.start_subtest(self._subtest_index + 1)
00663
00664
00665 def launch_pre_subtest(self):
00666 subtest = self._current_test.subtests[self._subtest_index]
00667
00668 if (subtest._pre_script is not None):
00669 script = subtest._pre_script
00670 pre_launcher = self.launch_file(script)
00671 if (pre_launcher == None):
00672 s = 'Could not load pre-subtest roslaunch script "%s"'%(os.path.basename(script))
00673 wx.MessageBox(s, 'Invalid roslaunch file', wx.OK|wx.ICON_ERROR, self)
00674 self.cancel(s)
00675 else:
00676 pre_launcher.spin()
00677
00678
00679 def launch_post_subtest(self):
00680 subtest = self._current_test.subtests[self._subtest_index]
00681
00682 if (subtest._post_script is not None):
00683 script = subtest._post_script
00684 post_launcher = self.launch_file(script)
00685 if (post_launcher == None):
00686 s = 'Could not load post-subtest roslaunch script "%s"'%(os.path.basename(script))
00687 wx.MessageBox(s, 'Invalid roslaunch file', wx.OK|wx.ICON_ERROR, self)
00688 self.cancel(s)
00689 else:
00690 post_launcher.spin()
00691
00692
00693
00694
00695 def launch_file(self, filename):
00696 with open(filename, 'r') as f:
00697 launch_xml = f.read()
00698
00699 return self.launch_script(launch_xml)
00700
00701
00702
00703 def launch_script(self, script):
00704 launch = roslaunch_caller.ScriptRoslaunch(script, None)
00705 try:
00706 launch.start()
00707 except Exception, e:
00708 traceback.print_exc()
00709 self.log('Caught exception launching file:\n%s' % traceback.format_exc())
00710 return None
00711
00712 return launch
00713
00714
00715 def on_spin(self, event):
00716 if (self._subtest_launch != None):
00717 self._subtest_launch.spin_once()
00718
00719 if (self._startup_launch != None):
00720 self._startup_launch.spin_once()
00721
00722 if (self._shutdown_launch != None):
00723 self._shutdown_launch.spin_once()
00724
00725 if (self._prestartup_launch != None):
00726 self._prestartup_launch.spin_once()
00727
00728 if (self._record_launch != None):
00729 self._record_launch.spin_once()
00730
00731
00732
00733
00734 def launches_running(self):
00735 if self._subtest_launch is not None: return True
00736 if self._startup_launch is not None: return True
00737 if self._shutdown_launch is not None: return True
00738 if self._prestartup_launch is not None: return True
00739 if self._record_launch is not None: return True
00740
00741 return False
00742
00743
00744 def stop_launches(self):
00745 self.log('Stopping launches')
00746
00747
00748 if self._subtest_launch is not None:
00749 self._subtest_launch.shutdown()
00750
00751 if self._startup_launch is not None:
00752 self._startup_launch.shutdown()
00753
00754 if self._shutdown_launch is not None:
00755 self._shutdown_launch.shutdown()
00756
00757 if self._prestartup_launch is not None:
00758 self._prestartup_launch.shutdown()
00759
00760 if self._record_launch is not None:
00761 self._record_launch.shutdown()
00762
00763
00764 if self._shutdown_done_srv is not None:
00765 self._shutdown_done_srv.shutdown()
00766
00767 if self._result_service is not None:
00768 self._result_service.shutdown()
00769
00770 if self._prestartup_done_srv is not None:
00771 self._prestartup_done_srv.shutdown()
00772
00773
00774 if self._subtest_timer is not None:
00775 self._subtest_timer.cancel()
00776
00777 if self._prestart_timer is not None:
00778 self._prestart_timer.cancel()
00779
00780 if self._shutdown_timer is not None:
00781 self._shutdown_timer.cancel()
00782
00783 self._subtest_timer = None
00784 self._prestart_timer = None
00785 self._shutdown_timer = None
00786
00787 self._result_service = None
00788 self._shutdown_done_srv = None
00789 self._prestartup_done_srv = None
00790
00791 self._startup_launch = None
00792 self._shutdown_launch = None
00793 self._prestartup_launch = None
00794 self._subtest_launch = None
00795 self._record_launch = None
00796
00797 self.log('Launches stopped.')
00798
00799
00800 def test_finished(self):
00801 if (self._current_test is not None and self._current_test.getShutdownScript() != None):
00802 self.log('Running shutdown script...')
00803
00804 if (self._shutdown_done_srv != None):
00805 self._shutdown_done_srv.shutdown()
00806 self._shutdown_done_srv = None
00807
00808 self._shutdown_done_srv = rospy.Service('shutdown_done', ScriptDone, self.shutdown_callback)
00809
00810 html = '<html><H2 align=center>Shutting down test and killing processes</H2></html>'
00811
00812 self._plots_panel.show_waiting(html, False)
00813 self.set_top_panel(self._plots_panel)
00814
00815
00816 shutdown_script = self._current_test.getShutdownScript()
00817 script = shutdown_script.launch_file
00818
00819 self._shutdown_launch = self.launch_file(script)
00820
00821 if self._shutdown_launch == None:
00822 s = 'Could not load roslaunch shutdown script "%s". SHUTDOWN POWER BOARD MANUALLY!'%(os.path.basename(script))
00823 wx.MessageBox(s, 'Invalid shutdown script!', wx.OK|wx.ICON_ERROR, self)
00824 self.log('No shutdown script: %s' % (s))
00825 self.log('SHUT DOWN POWER BOARD MANUALLY')
00826 return
00827
00828 if shutdown_script.get_timeout() > 0:
00829 timeout = shutdown_script.get_timeout()
00830 self._shutdown_timer = threading.Timer(timeout,
00831 self.shutdown_callback,
00832 [ script_timeout(timeout) ])
00833 self._shutdown_timer.start()
00834 else:
00835 self.log('No shutdown script')
00836 self.test_cleanup()
00837
00838
00839
00840 def shutdown_callback(self, srv):
00841 wx.CallAfter(self.shutdown_finished, srv)
00842 return ScriptDoneResponse()
00843
00844
00845 def shutdown_finished(self, srv):
00846 self.log('Shutdown finished')
00847
00848 if self._current_test is None:
00849 self.log('No test, how can I be shutting down?')
00850 return
00851
00852 if self._shutdown_launch is not None:
00853 self._shutdown_launch.shutdown()
00854 self._shutdown_launch = None
00855
00856 if self._shutdown_done_srv is not None:
00857 self._shutdown_done_srv.shutdown()
00858 self._shutdown_done_srv = None
00859
00860 if self._shutdown_timer is not None:
00861 self._shutdown_timer.cancel()
00862 self._shutdown_timer = None
00863
00864 self._results.add_shutdown_result(srv)
00865
00866 if srv.result != ScriptDoneRequest.RESULT_OK:
00867 fail_msg = 'Shutdown script failed!'
00868 wx.MessageBox(fail_msg + '\n' + srv.failure_msg, fail_msg, wx.OK|wx.ICON_ERROR, self)
00869 self.log('Shutdown failed for: %s' % srv.failure_msg)
00870
00871 self.test_cleanup()
00872
00873
00874 def test_cleanup(self):
00875 self.stop_launches()
00876
00877
00878
00879 self.show_results()
00880
00881 def start_continuous_testing(self):
00882 """
00883 Start continuous testing. Runs tests continuous until aborted.
00884 """
00885 if self._cont_frame:
00886 self._cont_frame.Raise()
00887 return
00888
00889 self.options.continuous = True
00890 self._cont_frame = cont_frame.ContinuousTestFrame(self)
00891 self._cont_frame.Show()
00892
00893 def stop_continuous_testing(self):
00894 """
00895 Stop continuous testing.
00896 """
00897 self.options.continuous = False
00898
00899 self._cont_frame.Close(True)
00900 self._cont_frame = None
00901
00902 def _handle_continuous_results(self):
00903 invent = self.get_inventory_object()
00904 self._cont_frame.new_results(self._results, invent)
00905 self.reset_params()
00906 self.begin_test(self._current_test, self._current_item)
00907
00908
00909 def show_results(self):
00910 if self.options.continuous:
00911 self._handle_continuous_results()
00912
00913 return
00914
00915 panel = ResultsPanel(self._top_panel, self._res, self)
00916 self.set_top_panel(panel)
00917
00918 self._waiting_for_submit = True
00919
00920 if self._results:
00921 self._results.write_results_to_file()
00922 panel.set_results(self._results)
00923 else:
00924 self.reset()
00925
00926
00927 def login_to_invent(self):
00928 dialog = self._res.LoadDialog(self, 'username_password_dialog')
00929 xrc.XRCCTRL(dialog, 'text').Wrap(300)
00930 dialog.Layout()
00931 dialog.Fit()
00932 username_ctrl = xrc.XRCCTRL(dialog, 'username')
00933 password_ctrl = xrc.XRCCTRL(dialog, 'password')
00934 username_ctrl.SetFocus()
00935
00936
00937 username_ctrl.SetMinSize(wx.Size(200, -1))
00938 password_ctrl.SetMinSize(wx.Size(200, -1))
00939 if (dialog.ShowModal() != wx.ID_OK):
00940 return False
00941
00942 username = username_ctrl.GetValue()
00943 password = password_ctrl.GetValue()
00944
00945 invent = Invent(username, password)
00946
00947 if (invent.login() == False):
00948 return self.login_to_invent()
00949
00950 rospy.set_param('/invent/username', username)
00951 rospy.set_param('/invent/password', password)
00952
00953 self._invent_client = invent
00954 return True
00955
00956
00957
00958 def get_inventory_object(self):
00959 if self._invent_client and self._invent_client.login():
00960 return self._invent_client
00961
00962 default_user = os.getenv('INVENT_USERNAME')
00963 default_pass = os.getenv('INVENT_PASSWORD')
00964
00965 if default_user and default_pass:
00966 iv = Invent(default_user, default_pass)
00967 if iv.login():
00968 self._invent_client = iv
00969
00970 rospy.set_param('/invent/username', default_user)
00971 rospy.set_param('/invent/password', default_pass)
00972 return self._invent_client
00973
00974 username = rospy.get_param('/invent/username', '')
00975 password = rospy.get_param('/invent/password', '')
00976
00977 if (username and password):
00978 invent = Invent(username, password)
00979 if (invent.login() == True):
00980 self._invent_client = invent
00981 return self._invent_client
00982
00983 rospy.set_param('/invent/username', '')
00984 rospy.set_param('/invent/password', '')
00985
00986 if not self.login_to_invent() or not self._invent_client or not self._invent_client.login():
00987 return None
00988 else:
00989
00990 return self._invent_client
00991
00992
00993 def verify_submit(self):
00994 submit_check = 'Are you sure you want to submit?\n\n'
00995 submit_check += 'Press OK to submit or Cancel to recheck results.\n'
00996 submit_check += 'Be sure to select the correct directory to record your results.\n'
00997
00998 are_you_sure = wx.MessageDialog(self, submit_check, 'Verify Results Submission',
00999 wx.OK|wx.CANCEL)
01000 return are_you_sure.ShowModal() == wx.ID_OK
01001
01002
01003
01004
01005 def submit_results(self, notes, directory):
01006 if not self.verify_submit():
01007 return
01008
01009 self._waiting_for_submit = False
01010
01011 if self._current_item is None:
01012 self.log('Can\'t submit, no item')
01013 self.reset()
01014 return
01015
01016 self._results.set_results_dir(directory)
01017
01018 invent = self.get_inventory_object()
01019 self._results.set_notes(notes)
01020 self._results.set_operator(rospy.get_param('invent/username', ''))
01021
01022 self.log('Results logged to %s' % self._results.results_dir)
01023 res, log_str = self._results.log_results(invent)
01024 self.log(log_str)
01025
01026 if not res:
01027 wx.MessageBox('Unable to submit qualification results to invent. This may be a problem in the inventory system.\nMessage:%s' % log_str, 'Invent Submit Failed', wx.OK|wx.ICON_ERROR, self)
01028
01029 if not self._results.email_qual_team():
01030 wx.MessageBox('Unable to email qualification results. Do you have \'sendmail\' installed?', 'Unable to email results', wx.OK|wx.ICON_ERROR, self)
01031 self.log('Unable to email summary.')
01032 else:
01033 self.log('Emailed summary to %s' % self._results.get_qual_team())
01034
01035 self.reset()
01036
01037
01038 def cancel(self, error = False):
01039 if self._results is not None:
01040 if error:
01041 self._results.error()
01042 else:
01043 self._results.cancel()
01044
01045 self.test_finished()
01046
01047
01048 def on_close(self, event):
01049 if event.CanVeto() and (self.launches_running() or self._waiting_for_submit):
01050 dialog = wx.MessageDialog(self, 'Are you sure you want to close this window? This will shut down the current test and discard results. Press "Cancel" to resume.', 'Confirm Close', wx.OK|wx.CANCEL)
01051 if dialog.ShowModal() != wx.ID_OK:
01052 event.Veto()
01053 return
01054
01055 event.Skip()
01056
01057 self.stop_launches()
01058 self.Destroy()
01059