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 from __future__ import with_statement
00039 PKG = 'life_test'
00040
00041 import roslib
00042 roslib.load_manifest(PKG)
00043
00044 import sys, os, math, string
00045 import csv
00046 import traceback
00047 from time import sleep, strftime, localtime
00048 import threading
00049 import socket, subprocess
00050
00051 import paramiko
00052 import Crypto
00053
00054 import wx
00055 from wx import xrc
00056
00057 import rospy
00058
00059 from std_srvs.srv import *
00060
00061
00062 from pr2_self_test_msgs.msg import TestStatus, TestInfo
00063
00064 from test_param import TestParam, LifeTest
00065 from test_record import TestRecord
00066 from writing_core import *
00067
00068 from runtime_monitor.monitor_panel import MonitorPanel
00069 from roslaunch_caller import roslaunch_caller
00070
00071 class TestMonitorPanel(wx.Panel):
00072 def __init__(self, parent, manager, test, serial):
00073 wx.Panel.__init__(self, parent)
00074
00075 self._manager = manager
00076
00077 self._mutex = threading.Lock()
00078
00079 self._status_sub = None
00080
00081
00082 self._test = test
00083 self._serial = serial
00084 self._record = TestRecord(test, serial)
00085
00086
00087 xrc_path = os.path.join(roslib.packages.get_pkg_dir('life_test'), 'xrc/gui.xrc')
00088
00089 self._panel = xrc.XmlResource(xrc_path).LoadPanel(self, 'test_panel')
00090 self._test_desc = xrc.XRCCTRL(self._panel, 'test_desc')
00091 self._test_desc.SetValue(self._test.desc)
00092
00093 self._launch_button = xrc.XRCCTRL(self._panel, 'launch_test_button')
00094 self._launch_button.Bind(wx.EVT_BUTTON, self.start_stop_test)
00095 self._launch_button.SetToolTip(wx.ToolTip("Start and stop the test"))
00096
00097 self._test_bay_ctrl = xrc.XRCCTRL(self._panel, 'test_bay_ctrl')
00098 self._test_bay_ctrl.SetItems(self._manager.room.get_bay_names(self._test.needs_power))
00099 self._test_bay_ctrl.SetToolTip(wx.ToolTip("Select location of test"))
00100
00101
00102 self._end_cond_type = xrc.XRCCTRL(self._panel, 'end_cond_type')
00103 self._end_cond_type_label = xrc.XRCCTRL(self._panel, 'duration_label')
00104 self._test_duration_ctrl = xrc.XRCCTRL(self._panel, 'test_duration_ctrl')
00105
00106 if self._test.duration > 0:
00107 self._end_cond_type.SetStringSelection('Hours')
00108 self._test_duration_ctrl.SetRange(0, max(168, self._test.duration))
00109 self._test_duration_ctrl.SetValue(int(self._test.duration))
00110 else:
00111 self._end_cond_type.SetStringSelection('Continuous')
00112 self._test_duration_ctrl.SetRange(0, 0)
00113 self._test_duration_ctrl.SetValue(0)
00114
00115
00116 self._end_cond_type.Bind(wx.EVT_CHOICE, self.on_end_choice)
00117 self._end_cond_type.SetToolTip(wx.ToolTip("Select stop time"))
00118
00119
00120 self._close_button = xrc.XRCCTRL(self._panel, 'close_button')
00121 self._close_button.Bind(wx.EVT_BUTTON, self.on_close)
00122 self._close_button.SetToolTip(wx.ToolTip("Close this test panel"))
00123
00124 self._status_bar = xrc.XRCCTRL(self._panel, 'test_status_bar')
00125 self._status_bar.SetToolTip(wx.ToolTip("Current status of this test"))
00126
00127
00128 self._reset_button = xrc.XRCCTRL(self._panel, 'reset_motors_button')
00129 self._reset_button.Bind(wx.EVT_BUTTON, self.on_reset_test)
00130 self._reset_button.SetToolTip(wx.ToolTip("Resume test operation"))
00131
00132 self._halt_button = xrc.XRCCTRL(self._panel, 'halt_motors_button')
00133 self._halt_button.Bind(wx.EVT_BUTTON, self.on_halt_test)
00134 self._reset_button.SetToolTip(wx.ToolTip("Pause test"))
00135
00136
00137 self._user_log = xrc.XRCCTRL(self._panel, 'user_log_input')
00138 self._user_log.SetToolTip(wx.ToolTip("Enter any user notes here"))
00139 self._user_submit = xrc.XRCCTRL(self._panel, 'user_submit_button')
00140 self._user_submit.Bind(wx.EVT_BUTTON, self.on_user_entry)
00141 self._user_submit.SetToolTip(wx.ToolTip("Submit entry to test log"))
00142
00143 self._done_time_ctrl = xrc.XRCCTRL(self._panel, 'done_time_ctrl')
00144 self._done_time_ctrl.SetToolTip(wx.ToolTip("Remaining time to completion"))
00145
00146 self._elapsed_time_ctrl = xrc.XRCCTRL(self._panel, 'elapsed_time_ctrl')
00147 self._elapsed_time_ctrl.SetToolTip(wx.ToolTip("Time since test was opened"))
00148 self._active_time_ctrl = xrc.XRCCTRL(self._panel, 'active_time_ctrl')
00149 self._active_time_ctrl.SetToolTip(wx.ToolTip("Total operating time of test"))
00150
00151 self._log_ctrl = xrc.XRCCTRL(self._panel, 'test_log')
00152 self._test_log_window = xrc.XRCCTRL(self._panel, 'test_log_window')
00153
00154
00155 self._power_board_text = xrc.XRCCTRL(self._panel, 'power_board_text')
00156 self._power_board_text.SetBackgroundColour("White")
00157 self._power_board_text.SetValue("Test Not Running")
00158
00159 self._estop_status = xrc.XRCCTRL(self._panel, 'estop_status')
00160 self._estop_status.SetValue("Test Not Running")
00161
00162 self._power_run_button = xrc.XRCCTRL(self._panel, 'power_run_button')
00163 self._power_run_button.Bind(wx.EVT_BUTTON, self.on_power_run)
00164 self._power_run_button.SetToolTip(wx.ToolTip("Turn on power"))
00165
00166 self._power_standby_button = xrc.XRCCTRL(self._panel, 'power_standby_button')
00167 self._power_standby_button.Bind(wx.EVT_BUTTON, self.on_power_standby)
00168 self._power_run_button.SetToolTip(wx.ToolTip("Turn power to standby"))
00169
00170 self._power_disable_button = xrc.XRCCTRL(self._panel, 'power_disable_button')
00171 self._power_disable_button.Bind(wx.EVT_BUTTON, self.on_power_disable)
00172 self._power_run_button.SetToolTip(wx.ToolTip("Turn power to disable"))
00173
00174
00175 self._power_sn_text = xrc.XRCCTRL(self._panel, 'power_sn_text')
00176 self._power_breaker_text = xrc.XRCCTRL(self._panel, 'power_breaker_text')
00177 self._machine_text = xrc.XRCCTRL(self._panel, 'machine_text')
00178
00179
00180 self._notebook = xrc.XRCCTRL(self._panel, 'test_data_notebook')
00181 wx.CallAfter(self._create_monitor)
00182
00183 self._sizer = wx.BoxSizer(wx.HORIZONTAL)
00184 self._sizer.Add(self._panel, 1, wx.EXPAND)
00185 self.SetSizer(self._sizer)
00186 self.Layout()
00187
00188 self._bay = None
00189 self._current_log = {}
00190 self._diag_msgs = {}
00191
00192
00193 self._is_running = False
00194 self._stat_level = 127
00195 self._test_msg = 'None'
00196 self._power_stat = "No data"
00197 self._estop_stat = False
00198 self._stop_count = 0
00199
00200
00201 self._test_launcher = None
00202
00203
00204 self.timer = wx.Timer(self)
00205 self.Bind(wx.EVT_TIMER, self.on_timer, self.timer)
00206 self._last_message_time = rospy.get_time()
00207 self._timeout_interval = 10.0
00208 self._is_stale = True
00209 self.timer.Start(1000 * self._timeout_interval)
00210
00211
00212 self.power_timer = wx.Timer(self)
00213 self.Bind(wx.EVT_TIMER, self.on_power_timer, self.power_timer)
00214 self.last_power_update = rospy.get_time()
00215 self.power_timeout = 5.0
00216
00217
00218 self.invent_timer = wx.Timer(self)
00219 self.Bind(wx.EVT_TIMER, self.on_invent_timer, self.invent_timer)
00220 self.invent_timeout = 600
00221 self.invent_timer.Start(self.invent_timeout * 500)
00222 self._is_invent_stale = True
00223
00224 self._update_controls()
00225 self._enable_controls()
00226
00227 def _create_monitor(self):
00228 """
00229 Loads runtime_monitor panel. Called after to make display work
00230 """
00231 self._monitor_panel = MonitorPanel(self._notebook, 'empty_topic')
00232 self._monitor_panel.SetSize(wx.Size(400, 500))
00233 self._notebook.AddPage(self._monitor_panel, "Diagnostics")
00234 self._notebook.ChangeSelection(0)
00235
00236 @property
00237 def launched(self):
00238 return self._test_launcher is not None
00239
00240 def on_end_choice(self, event = None):
00241 choice = self._end_cond_type.GetStringSelection()
00242
00243
00244 label = choice.lower()
00245 if choice == 'Continuous':
00246 label = 'N/A'
00247 self._end_cond_type_label.SetLabel(choice.lower())
00248
00249
00250 self._test_duration_ctrl.SetValue(0)
00251 active_time = self._record.get_cum_time()
00252
00253 if choice == 'Hours':
00254 hrs = math.ceil((active_time / 3600))
00255 self._test_duration_ctrl.SetRange(hrs, 168)
00256 self._test_duration_ctrl.SetValue(hrs)
00257 elif choice == 'Minutes':
00258 minv = math.ceil((active_time / 60))
00259 self._test_duration_ctrl.SetRange(minv, 600)
00260 self._test_duration_ctrl.SetValue(minv + 10)
00261 else:
00262 self._test_duration_ctrl.SetRange(0, 0)
00263 self._test_duration_ctrl.SetValue(0)
00264
00265 def on_close(self, event):
00266 if not self._record.test_complete:
00267 dialog = wx.MessageDialog(self, 'WARNING: Test is not complete. Has the test run for the full alloted time? Press OK to close this window anyway.', 'Test Not Complete', wx.OK|wx.CANCEL)
00268 if dialog.ShowModal() != wx.ID_OK:
00269 return
00270
00271 try:
00272 self.update_test_record('Closing down test.')
00273 self.record_test_log()
00274
00275 if self._bay is not None:
00276 self._manager.test_stop(self._bay)
00277 except Exception, e:
00278 rospy.logerr('Exception on close: %s' % traceback.format_exc())
00279
00280 if self.launched:
00281 self.stop_test()
00282
00283 if self._status_sub is not None:
00284 self._status_sub.unregister()
00285 self._status_sub = None
00286
00287 self._monitor_panel.shutdown()
00288
00289 self._manager.close_tab(self._serial)
00290
00291 def on_user_entry(self, event):
00292 entry = self._user_log.GetValue()
00293 msg = 'OPERATOR: ' + entry
00294 self.update_test_record(msg)
00295 self._user_log.Clear()
00296 self._user_log.SetFocus()
00297
00298
00299 def update_test_record(self, note = ''):
00300 alert, msg = self._record.update(self.launched, self._is_running, self._is_stale,
00301 note, self._test_msg)
00302 message = msg + ' ' + note
00303
00304 if alert > 0 or note != '':
00305 self._current_log[rospy.get_time()] = message
00306 self._display_logs()
00307
00308
00309
00310 def _display_logs(self):
00311 kys = dict.keys(self._current_log)
00312 kys.sort()
00313
00314 log_str = ''
00315 for ky in kys:
00316 log_str += strftime("%m/%d/%Y %H:%M:%S: ",
00317 localtime(ky)) + self._current_log[ky] + '\n'
00318
00319 self._log_ctrl.AppendText(log_str)
00320
00321
00322 self._test_log_window.Freeze()
00323 (x, y) = self._test_log_window.GetViewStart()
00324 self._test_log_window.SetPage(self._record.write_log())
00325 self._test_log_window.Scroll(x, y)
00326 self._test_log_window.Thaw()
00327
00328 self._current_log = {}
00329
00330 def _calc_run_time(self):
00331 end_condition = self._end_cond_type.GetStringSelection()
00332
00333 duration = self._test_duration_ctrl.GetValue()
00334
00335 if end_condition == 'Hours':
00336 return duration * 3600
00337 if end_condition == 'Minutes':
00338 return duration * 60
00339 if end_condition == 'Seconds':
00340 return duration
00341 else:
00342 return 10**10
00343
00344 def _calc_remaining(self):
00345 total_sec = self._calc_run_time()
00346 cum_sec = self._record.get_cum_time()
00347
00348 return total_sec - cum_sec
00349
00350 def on_timer(self, event):
00351 if not self.launched:
00352 return
00353
00354 interval = rospy.get_time() - self._last_message_time
00355
00356 was_stale = self._is_stale
00357
00358 if interval > 180:
00359 self._is_running = False
00360 self._is_stale = True
00361
00362 if not was_stale:
00363 rospy.logerr('Stopping test on machine %s. Update is stale for %d seconds' % (self._bay.name, int(interval)))
00364 self.update_test_record('Stopping test after no data received for %d seconds.' % int(interval))
00365
00366 self.stop_test()
00367 self.update_test_record('Test on %s was stopped after no updates, but is incomplete' % self._serial)
00368
00369 self._update_controls(4)
00370 self.update_test_record()
00371 self.stop_if_done()
00372 else:
00373 self._is_stale = False
00374
00375 def on_status_check(self):
00376 msg = TestInfo()
00377 msg.serial = str(self._serial)
00378 msg.test_name = str(self._test.short)
00379 if self.launched:
00380 msg.test_status = int(self._stat_level)
00381 msg.bay_name = str(self._bay.name)
00382 msg.machine = str(self._bay.machine)
00383 if self._bay.board is not None and self._test.needs_power:
00384 msg.board = self._bay.board
00385 msg.breaker = self._bay.breaker
00386 msg.power_status = self._power_stat
00387 if self._estop_stat:
00388 msg.estop = 1
00389 else:
00390 msg.estop = 0
00391 else:
00392 msg.board = 0
00393 msg.breaker = 0
00394
00395 else:
00396 msg.test_status = 127
00397 msg.bay_name = "None"
00398 msg.board = 0
00399 msg.breaker = 0
00400 msg.machine = ""
00401
00402 msg.elapsed = self._record.get_cum_time()
00403 msg.status_msg = self._test_msg
00404
00405 return msg
00406
00407 def _test_power_cmd(self):
00408 if not self.launched:
00409 wx.MessageBox('Test is not launched. Unable to command power board', 'Test is not launched', wx.OK|wx.ICON_ERROR, self)
00410 return False
00411
00412 if self._bay.board is None:
00413 wx.MessageBox('Test bay has no power board. Unable to command power board', 'No Power Board',
00414 wx.OK|wx.ICON_ERROR, self)
00415 return False
00416 return True
00417
00418 def on_power_run(self, event):
00419 self.update_test_record("Turning on power.")
00420 if not self._test_power_cmd():
00421 return
00422
00423 if not self._manager.power_run(self._bay):
00424 self.update_test_record("Unable to command power board.")
00425 wx.MessageBox('Unable to run power board. Board: %d, breaker: %d' % (self._bay.board, self._bay.breaker), wx.OK|wx.ICON_ERROR, self)
00426
00427 def on_power_standby(self, event):
00428 self.update_test_record("Setting power to standby.")
00429 if not self._test_power_cmd():
00430 return
00431
00432 if not self._manager.power_standby(self._bay):
00433 self.update_test_record("Unable to command power board.")
00434 wx.MessageBox('Unable to standby power board. Board: %d, breaker: %d' % (self._bay.board, self._bay.breaker), wx.OK|wx.ICON_ERROR, self)
00435
00436 def on_power_disable(self, event):
00437 self.update_test_record("Setting power to disable.")
00438 if not self._test_power_cmd():
00439 return
00440
00441 if not self._manager.power_disable(self._bay):
00442 self.update_test_record("Unable to command power board.")
00443 wx.MessageBox('Unable to disable power board. Board: %d, breaker: %d' % (self._bay.board, self._bay.breaker), wx.OK|wx.ICON_ERROR, self)
00444
00445 def start_power_timer(self):
00446 self.power_timer.Start(1000 * self.power_timeout, True)
00447
00448 def on_power_timer(self, event = None):
00449 if rospy.get_time() - self.last_power_update > self.power_timeout:
00450 self.update_board("Stale", False)
00451
00452
00453 def update_board(self, value, estop):
00454 if not self.launched:
00455 return
00456
00457 self._power_stat = value
00458 self._estop_stat = estop
00459
00460 self.start_power_timer()
00461
00462 if value == "Stale":
00463 self._power_board_text.SetBackgroundColour("Light Blue")
00464 self._power_board_text.SetValue("Stale")
00465 self._estop_status.SetBackgroundColour("Light Blue")
00466 self._estop_status.SetValue("E-Stop Stale")
00467 return
00468
00469 elif value == "Standby":
00470 self._power_board_text.SetBackgroundColour("Orange")
00471 self._power_board_text.SetValue("Standby")
00472 elif value == "On":
00473 self._power_board_text.SetBackgroundColour("Light Green")
00474 self._power_board_text.SetValue("Running")
00475 else:
00476 self._power_board_text.SetBackgroundColour("Red")
00477 self._power_board_text.SetValue("Disabled")
00478
00479 if not estop:
00480 self._estop_status.SetBackgroundColour("Red")
00481 self._estop_status.SetValue("E-Stop Hit")
00482 else:
00483 self._estop_status.SetBackgroundColour("Light Green")
00484 self._estop_status.SetValue("E-Stop OK")
00485
00486
00487
00488 def _update_status_bar(self, level, msg):
00489 if not self.launched:
00490 self._status_bar.SetValue("Launch to display status")
00491 self._status_bar.SetBackgroundColour("White")
00492 elif level == 0:
00493 self._status_bar.SetValue("Test Running: OK")
00494 self._status_bar.SetBackgroundColour("Light Green")
00495 elif level == 1:
00496 self._status_bar.SetValue("Warning: %s" % msg)
00497 self._status_bar.SetBackgroundColour("Orange")
00498 elif level == 2:
00499 self._status_bar.SetValue("Error: %s" % msg)
00500 self._status_bar.SetBackgroundColour("Red")
00501 elif level == 3:
00502 self._status_bar.SetValue("Stale Reported: %s" % msg)
00503 self._status_bar.SetBackgroundColour("Light Blue")
00504 else:
00505 self._status_bar.SetBackgroundColour("Light Blue")
00506 self._status_bar.SetValue("Test Monitor: No Updates/Stale")
00507
00508
00509 def _update_controls(self, level = 4, msg = 'None'):
00510 self._update_status_bar(level, msg)
00511
00512
00513 self._stat_level = level
00514 self._test_msg = msg
00515
00516 remaining = self._calc_remaining()
00517 remain_str = "N/A"
00518 if remaining < 10**6:
00519 remain_str = get_duration_str(remaining)
00520 self._done_time_ctrl.SetValue(remain_str)
00521
00522 self._active_time_ctrl.SetValue(self._record.get_active_str())
00523 self._elapsed_time_ctrl.SetValue(self._record.get_elapsed_str())
00524
00525
00526 def _enable_controls(self):
00527 self._reset_button.Enable(self.launched)
00528 self._halt_button.Enable(self.launched)
00529
00530 self._test_bay_ctrl.Enable(not self.launched)
00531 self._close_button.Enable(not self.launched)
00532
00533
00534 self._power_run_button.Enable(self.launched and self._bay.board is not None)
00535 self._power_standby_button.Enable(self.launched and self._bay.board is not None)
00536 self._power_disable_button.Enable(self.launched and self._bay.board is not None)
00537
00538 if self.launched:
00539 self._launch_button.SetLabel("Stop")
00540 else:
00541 self._launch_button.SetLabel("Launch")
00542
00543 def stop_if_done(self):
00544 remain = self._calc_remaining()
00545
00546 if remain < 0:
00547 self._stop_count += 1
00548 else:
00549 self._stop_count = 0
00550
00551
00552
00553 if self._stop_count > 5 and not self._record.test_complete:
00554 self._record.complete_test()
00555 self.stop_test()
00556 self._enable_controls()
00557
00558 def _status_callback(self, msg):
00559 """
00560 Callback from BAY/test_status topic
00561 """
00562 with self._mutex:
00563 self._status_msg = msg
00564
00565 wx.CallAfter(self._new_msg)
00566
00567 def _new_msg(self):
00568 """
00569 Updates state with new data from test_status
00570 """
00571 with self._mutex:
00572 test_level = self._status_msg.test_ok
00573 test_msg = self._status_msg.message
00574
00575 self._last_message_time = rospy.get_time()
00576
00577 self._is_running = (test_level == 0)
00578 self._is_stale = False
00579
00580 self._update_controls(test_level, test_msg)
00581 self.update_test_record()
00582 self.stop_if_done()
00583
00584
00585 def make_launch_script(self, bay, script, local_diag_topic):
00586
00587 os.environ['ROS_NAMESPACE'] = bay.name
00588
00589 launch = '<launch>\n'
00590 launch += '<group ns="%s" >\n' % bay.name
00591
00592
00593
00594 launch += '<remap from="/diagnostics" to="%s" />\n' % local_diag_topic
00595 launch += '<remap from="/tf" to="/%s/tf" />\n' % bay.name
00596
00597
00598
00599 launch += '<machine name="test_host" address="%s" default="true" ' % bay.machine
00600 launch += 'ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" timeout="15" />\n'
00601
00602
00603 launch += '<machine name="localhost" address="localhost" '
00604 launch += 'ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" timeout="20" default="false"/>\n'
00605
00606
00607 launch += '<include file="$(find life_test)/%s" />\n' % script
00608
00609
00610 launch += ' <node machine="localhost" pkg="rosbag" type="rosbag" '
00611 launch += 'args="record -o /hwlog/%s_life_test /diagnostics --split 1000" name="test_logger" />\n' % self._serial
00612
00613
00614 launch += ' <node machine="localhost" pkg="rosbag" type="rosbag" name="mtrace_record" '
00615 launch += 'args="record -o /hwlog/%s_motor_trace -e /%s/motor_trace/.* " />\n' % (self._serial, bay.name)
00616
00617 launch += '</group>\n</launch>'
00618
00619 return launch
00620
00621
00622 def start_stop_test(self, event):
00623 if self.launched:
00624 if not self.stop_test_user():
00625 return
00626 else:
00627 if not self.launch_test():
00628 return
00629
00630 self._update_controls()
00631 self._enable_controls()
00632
00633
00634 def stop_test_user(self):
00635 dialog = wx.MessageDialog(self, 'Are you sure you want to stop this test?', 'Confirm Stop Test', wx.OK|wx.CANCEL)
00636 if dialog.ShowModal() != wx.ID_OK:
00637 return False
00638
00639 self.stop_test()
00640 return True
00641
00642 def _tear_down_test(self):
00643 """
00644 Reset displays and state. Shut down test processes
00645 """
00646
00647 self._launch_button.Enable(False)
00648
00649
00650 self.on_halt_test(None)
00651
00652
00653 self._power_board_text.SetBackgroundColour("White")
00654 self._power_board_text.SetValue("Test Not Running")
00655 self._estop_status.SetBackgroundColour("White")
00656 self._estop_status.SetValue("Test Not Running")
00657 self._machine_text.SetValue("Not running")
00658 self._power_sn_text.SetValue("Not running")
00659 self._power_breaker_text.SetValue("Not running")
00660
00661
00662 if self._bay.board is not None:
00663 if not self._manager.power_disable(self._bay):
00664 wx.MessageBox("Power disable command failed. Unable to command power board", "Power command failed", wx.OK|wx.ICON_ERROR, self)
00665
00666
00667
00668 try:
00669 if self._test_launcher:
00670 self._test_launcher.shutdown()
00671 except Exception, e:
00672 rospy.logerr('Unable to shutdown test')
00673 rospy.logerr(traceback.format_exc())
00674 self.update_test_record(traceback.format_exc())
00675
00676 self._manager.test_stop(self._bay)
00677 self.update_test_record('Shutting down test processes.')
00678
00679
00680 self._is_running = False
00681 self._test_launcher = None
00682 self._bay = None
00683 self._record.set_bay(None)
00684
00685
00686 self._launch_button.Enable(True)
00687 self._update_controls()
00688 self._enable_controls()
00689
00690 def stop_test(self):
00691 if self.launched:
00692 self._tear_down_test()
00693
00694 if self._status_sub:
00695 self._status_sub.unregister()
00696 self._status_sub = None
00697
00698 self._monitor_panel.change_diagnostic_topic('empty')
00699
00700 self._is_running = False
00701
00702 def _check_machine(self, bay):
00703 """
00704 Check the machine is online.
00705
00706 @return True if machine is OK
00707 """
00708 try:
00709 machine_addr = socket.gethostbyname(bay.machine)
00710 except socket.gaierror:
00711 wx.MessageBox('Hostname "%s" (bay "%s") is invalid. The machine may be offline or disconnected.' % (bay.machine, bay.name),
00712 'Test Bay Invalid', wx.OK|wx.ICON_ERROR)
00713 return False
00714
00715
00716 retcode = subprocess.call('ping -c1 -W1 %s > /dev/null' % bay.machine, shell=True)
00717 if retcode != 0:
00718 wx.MessageBox('Cannot contact machine "%s" for bay "%s". It may be offline or disconnected. Check the machine and retry.' % (bay.machine, bay.name),
00719 'Test Bay Unavailable', wx.OK|wx.ICON_ERROR)
00720 return False
00721
00722 return True
00723
00724 def _check_keys(self, bay):
00725 """
00726 Check that machine has valid keys for remote launching
00727
00728 Uses paramiko to make sure it can open a connection to the remote machine. Will open a message box with
00729 error message if it is unable to log in. Returns False if failure, True if OK.
00730 """
00731 ssh = paramiko.SSHClient()
00732
00733
00734 try:
00735 if os.path.isfile('/etc/ssh/ssh_known_hosts'):
00736 ssh.load_system_host_keys('/etc/ssh/ssh_known_hosts')
00737 except IOError:
00738 pass
00739
00740 try:
00741 ssh.load_system_host_keys()
00742 except IOError:
00743 wx.MessageBox('Unable to load host keys from ~/.ssh/known_hosts. File may be corrupt. Run "rm ~/.ssh/known_hosts" to attempt to clear this problem',
00744 'Launch Error - Known Hosts', wx.OK)
00745
00746
00747 ssh.set_missing_host_key_policy(paramiko.AutoAddPolicy())
00748
00749 try:
00750 ssh.connect(bay.machine, 22, None, timeout=10)
00751 except paramiko.BadHostKeyException:
00752 wx.MessageBox('Unable to verify host key for machine %s. Check authetication with "ssh MACHINE"' % bay.machine,
00753 'Bad Host Key', wx.OK|wx.ICON_ERROR)
00754 return False
00755 except paramiko.AuthenticationException:
00756 wx.MessageBox('Unable to log in to remote machine %s. Authentication failed. Machine may not be configured.' % bay.machine,
00757 'Authentication Failed', wx.OK|wx.ICON_ERROR)
00758 return False
00759 except paramiko.SSHException:
00760 wx.MessageBox('Unable to launch. Unknown server %s. Machine may be invalid.' % bay.machine,
00761 'Unknown Server', wx.OK|wx.ICON_ERROR)
00762 return False
00763 except Exception:
00764 wx.MessageBox('Unable to launch on machine %s. Unknown exception' % bay.machine,
00765 'Unknown Launching Exception', wx.OK|wx.ICON_ERROR)
00766 import traceback
00767 self.update_test_record(traceback.format_exc())
00768 return False
00769
00770 ssh.close()
00771
00772 return True
00773
00774 def _load_bay(self):
00775 """
00776 Checks that the bay is valid, reserves bay, runs power.
00777
00778 @return None if bay invalid
00779 """
00780 bay_name = self._test_bay_ctrl.GetStringSelection()
00781 bay = self._manager.room.get_bay(bay_name)
00782 if bay is None:
00783 wx.MessageBox('Select test bay', 'Select Bay', wx.OK|wx.ICON_ERROR, self)
00784 return None
00785
00786 return bay
00787
00788
00789 def _enable_bay(self):
00790 """
00791 Reserve bay from manager, enable power
00792
00793 @return False if unable to reserve bay or enable power
00794 """
00795 if not self._manager.test_start_check(self._bay, self._serial):
00796 wx.MessageBox('Test bay in use, select again!', 'Test bay in use', wx.OK|wx.ICON_ERROR, self)
00797 return False
00798
00799 if self._bay.board is not None:
00800 if not self._manager.power_run(self._bay):
00801 wx.MessageBox('Unable to command power board. Check connections. Board: %s, Breaker %d' % (self._bay.board, self._bay.breaker), 'Power Command Failure', wx.OK|wx.ICON_ERROR, self)
00802 self._manager.test_stop(self._bay)
00803 return False
00804
00805 return True
00806
00807 def _check_test_ready(self):
00808 """
00809 Check if test has <0 time remaining.
00810
00811 @return False if test has no time left
00812 """
00813 if self._calc_remaining() <= 0:
00814 wx.MessageBox('Test has no allowable time left. Add more hours/minutes and retry.',
00815 'Out of Time', wx.OK|wx.ICON_ERROR, self)
00816 return False
00817 return True
00818
00819 def _confirm_launch(self):
00820 """
00821 Checks with user to make sure test can start.
00822
00823 @return True if user is OK
00824 """
00825 dialog = wx.MessageDialog(self, 'Are you sure you want to launch?', 'Confirm Launch', wx.OK|wx.CANCEL)
00826 ok = dialog.ShowModal() == wx.ID_OK
00827 dialog.Destroy()
00828
00829 return ok
00830
00831 def launch_test(self):
00832 """
00833 Launches test on correct bay
00834
00835 @return False if launch failed or aborted
00836 """
00837
00838 self._launch_button.Enable(False)
00839
00840
00841 if not self._check_test_ready():
00842 self._launch_button.Enable(True)
00843 return False
00844
00845
00846 bay = self._load_bay()
00847 if not bay:
00848 self._launch_button.Enable(True)
00849 return False
00850
00851
00852 if not self._check_machine(bay):
00853 self._launch_button.Enable(True)
00854 return False
00855
00856
00857 if not self._check_keys(bay):
00858 self._launch_button.Enable(True)
00859 return False
00860
00861
00862 if not self._confirm_launch():
00863 self._launch_button.Enable(True)
00864 return False
00865
00866 self._bay = bay
00867 self._record.set_bay(self._bay)
00868
00869
00870 if not self._enable_bay():
00871 self._launch_button.Enable(True)
00872 self._bay = None
00873 self._record.set_bay(None)
00874 return False
00875
00876
00877 self._machine_text.SetValue(self._bay.machine)
00878 if self._bay.board is not None and self._test.needs_power:
00879 self._power_sn_text.SetValue(str(self._bay.board))
00880 self._power_breaker_text.SetValue(str(self._bay.breaker))
00881 self._power_board_text.SetValue("No data")
00882 self._power_board_text.SetBackgroundColour("Light Blue")
00883 self._estop_status.SetValue("No data")
00884 self._estop_status.SetBackgroundColour("Light Blue")
00885 self._power_stat = "No data"
00886 self._estop_stat = False
00887 else:
00888 self._power_sn_text.SetValue("No board")
00889 self._power_breaker_text.SetValue("No breaker")
00890 self._power_board_text.SetValue("No board")
00891 self._power_board_text.SetBackgroundColour("White")
00892 self._estop_status.SetBackgroundColour("White")
00893 self._estop_status.SetValue("No board")
00894
00895 self.update_test_record('Launching test %s on bay %s, machine %s.' % (self._test._name, self._bay.name, self._bay.machine))
00896
00897 self._last_message_time = rospy.get_time()
00898
00899
00900 local_diag = '/' + self._bay.name + '/diagnostics'
00901
00902
00903 rospy.set_param(self._bay.name, {})
00904 self._test.set_params(self._bay.name)
00905 self._test_launcher = roslaunch_caller.ScriptRoslaunch(
00906 self.make_launch_script(self._bay, self._test.launch_file, local_diag))
00907 try:
00908 self._test_launcher.start()
00909 except Exception, e:
00910 traceback.print_exc()
00911 self.update_test_record('Failed to launch script, caught exception.')
00912 self.update_test_record(traceback.format_exc())
00913 self._tear_down_test()
00914 self._launch_button.Enable(True)
00915
00916 wx.MessageBox('Failed to launch. Check machine for connectivity. See log for error message.', 'Failure to launch', wx.OK|wx.ICON_ERROR, self)
00917 return False
00918
00919
00920 local_status = '/' + str(self._bay.name) + '/test_status'
00921 self._is_running = False
00922 self._monitor_panel.change_diagnostic_topic(local_diag)
00923 self._status_sub = rospy.Subscriber(local_status, TestStatus, self._status_callback)
00924
00925 self._update_controls()
00926 self._enable_controls()
00927 self._launch_button.Enable(True)
00928
00929 return True
00930
00931 def on_halt_test(self, event = None):
00932 """
00933 Calls halt_test service to test monitor
00934 """
00935 try:
00936 self.update_test_record('Pausing test.')
00937 halt_srv = rospy.ServiceProxy(self._bay.name + '/halt_test', Empty)
00938 halt_srv()
00939
00940 return True
00941
00942 except Exception, e:
00943 rospy.logerr('Exception on halt test.\n%s' % traceback.format_exc())
00944
00945 self.update_test_record('Unable to reset test, caught exception: %s' % e)
00946 return False
00947
00948 def on_reset_test(self, event = None):
00949 """
00950 Calls reset_test service to test monitor
00951 """
00952 try:
00953 self.update_test_record('Resetting test.')
00954 reset = rospy.ServiceProxy(self._bay.name + '/reset_test', Empty)
00955 reset()
00956
00957 return True
00958
00959 except Exception, e:
00960 rospy.logerr('Exception on reset test.\n%s' % traceback.format_exc())
00961 self.update_test_record('Unable to reset test, caught exception: %s' % e)
00962 return False
00963
00964
00965 def record_test_log(self):
00966 """
00967 Called when test is closing down.
00968 """
00969 self._record.load_attachments(self._manager.invent_client)
00970
00971 def on_invent_timer(self, event):
00972 """
00973 Update inventory system with a note on progress every 10 minutes
00974 """
00975 self._record.update_invent(self._manager.invent_client)
00976
00977
00978