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 try:
00367 self.stop_test()
00368 except Exception, e:
00369 import traceback
00370 rospy.logerr(traceback.format_exc())
00371 self.update_test_record('Shutdown error: %s' % traceback.format_exc())
00372 self.update_test_record('Test on %s was stopped after no updates, but is incomplete' % self._serial)
00373
00374 self._update_controls(4)
00375 self.update_test_record()
00376 self.stop_if_done()
00377 else:
00378 self._is_stale = False
00379
00380 def on_status_check(self):
00381 msg = TestInfo()
00382 msg.serial = str(self._serial)
00383 msg.test_name = str(self._test.short)
00384 if self.launched:
00385 msg.test_status = int(self._stat_level)
00386 msg.bay_name = str(self._bay.name)
00387 msg.machine = str(self._bay.machine)
00388 if self._bay.board is not None and self._test.needs_power:
00389 msg.board = self._bay.board
00390 msg.breaker = self._bay.breaker
00391 msg.power_status = self._power_stat
00392 if self._estop_stat:
00393 msg.estop = 1
00394 else:
00395 msg.estop = 0
00396 else:
00397 msg.board = 0
00398 msg.breaker = 0
00399
00400 else:
00401 msg.test_status = 127
00402 msg.bay_name = "None"
00403 msg.board = 0
00404 msg.breaker = 0
00405 msg.machine = ""
00406
00407 msg.elapsed = self._record.get_cum_time()
00408 msg.status_msg = self._test_msg
00409
00410 return msg
00411
00412 def _test_power_cmd(self):
00413 if not self.launched:
00414 wx.MessageBox('Test is not launched. Unable to command power board', 'Test is not launched', wx.OK|wx.ICON_ERROR, self)
00415 return False
00416
00417 if self._bay.board is None:
00418 wx.MessageBox('Test bay has no power board. Unable to command power board', 'No Power Board',
00419 wx.OK|wx.ICON_ERROR, self)
00420 return False
00421 return True
00422
00423 def on_power_run(self, event):
00424 self.update_test_record("Turning on power.")
00425 if not self._test_power_cmd():
00426 return
00427
00428 if not self._manager.power_run(self._bay):
00429 self.update_test_record("Unable to command power board.")
00430 wx.MessageBox('Unable to run power board. Board: %d, breaker: %d' % (self._bay.board, self._bay.breaker), wx.OK|wx.ICON_ERROR, self)
00431
00432 def on_power_standby(self, event):
00433 self.update_test_record("Setting power to standby.")
00434 if not self._test_power_cmd():
00435 return
00436
00437 if not self._manager.power_standby(self._bay):
00438 self.update_test_record("Unable to command power board.")
00439 wx.MessageBox('Unable to standby power board. Board: %d, breaker: %d' % (self._bay.board, self._bay.breaker), wx.OK|wx.ICON_ERROR, self)
00440
00441 def on_power_disable(self, event):
00442 self.update_test_record("Setting power to disable.")
00443 if not self._test_power_cmd():
00444 return
00445
00446 if not self._manager.power_disable(self._bay):
00447 self.update_test_record("Unable to command power board.")
00448 wx.MessageBox('Unable to disable power board. Board: %d, breaker: %d' % (self._bay.board, self._bay.breaker), wx.OK|wx.ICON_ERROR, self)
00449
00450 def start_power_timer(self):
00451 self.power_timer.Start(1000 * self.power_timeout, True)
00452
00453 def on_power_timer(self, event = None):
00454 if rospy.get_time() - self.last_power_update > self.power_timeout:
00455 self.update_board("Stale", False)
00456
00457
00458 def update_board(self, value, estop):
00459 if not self.launched:
00460 return
00461
00462 self._power_stat = value
00463 self._estop_stat = estop
00464
00465 self.start_power_timer()
00466
00467 if value == "Stale":
00468 self._power_board_text.SetBackgroundColour("Light Blue")
00469 self._power_board_text.SetValue("Stale")
00470 self._estop_status.SetBackgroundColour("Light Blue")
00471 self._estop_status.SetValue("E-Stop Stale")
00472 return
00473
00474 elif value == "Standby":
00475 self._power_board_text.SetBackgroundColour("Orange")
00476 self._power_board_text.SetValue("Standby")
00477 elif value == "On":
00478 self._power_board_text.SetBackgroundColour("Light Green")
00479 self._power_board_text.SetValue("Running")
00480 else:
00481 self._power_board_text.SetBackgroundColour("Red")
00482 self._power_board_text.SetValue("Disabled")
00483
00484 if not estop:
00485 self._estop_status.SetBackgroundColour("Red")
00486 self._estop_status.SetValue("E-Stop Hit")
00487 else:
00488 self._estop_status.SetBackgroundColour("Light Green")
00489 self._estop_status.SetValue("E-Stop OK")
00490
00491
00492
00493 def _update_status_bar(self, level, msg):
00494 if not self.launched:
00495 self._status_bar.SetValue("Launch to display status")
00496 self._status_bar.SetBackgroundColour("White")
00497 elif level == 0:
00498 self._status_bar.SetValue("Test Running: OK")
00499 self._status_bar.SetBackgroundColour("Light Green")
00500 elif level == 1:
00501 self._status_bar.SetValue("Warning: %s" % msg)
00502 self._status_bar.SetBackgroundColour("Orange")
00503 elif level == 2:
00504 self._status_bar.SetValue("Error: %s" % msg)
00505 self._status_bar.SetBackgroundColour("Red")
00506 elif level == 3:
00507 self._status_bar.SetValue("Stale Reported: %s" % msg)
00508 self._status_bar.SetBackgroundColour("Light Blue")
00509 else:
00510 self._status_bar.SetBackgroundColour("Light Blue")
00511 self._status_bar.SetValue("Test Monitor: No Updates/Stale")
00512
00513
00514 def _update_controls(self, level = 4, msg = 'None'):
00515 self._update_status_bar(level, msg)
00516
00517
00518 self._stat_level = level
00519 self._test_msg = msg
00520
00521 remaining = self._calc_remaining()
00522 remain_str = "N/A"
00523 if remaining < 10**6:
00524 remain_str = get_duration_str(remaining)
00525 self._done_time_ctrl.SetValue(remain_str)
00526
00527 self._active_time_ctrl.SetValue(self._record.get_active_str())
00528 self._elapsed_time_ctrl.SetValue(self._record.get_elapsed_str())
00529
00530
00531 def _enable_controls(self):
00532 self._reset_button.Enable(self.launched)
00533 self._halt_button.Enable(self.launched)
00534
00535 self._test_bay_ctrl.Enable(not self.launched)
00536 self._close_button.Enable(not self.launched)
00537
00538
00539 self._power_run_button.Enable(self.launched and self._bay.board is not None)
00540 self._power_standby_button.Enable(self.launched and self._bay.board is not None)
00541 self._power_disable_button.Enable(self.launched and self._bay.board is not None)
00542
00543 if self.launched:
00544 self._launch_button.SetLabel("Stop")
00545 else:
00546 self._launch_button.SetLabel("Launch")
00547
00548 def stop_if_done(self):
00549 remain = self._calc_remaining()
00550
00551 if remain < 0:
00552 if self._bay and self._bay.name:
00553 rospy.loginfo("zero time remaining on bay %s" % self._bay.name)
00554 else:
00555 rospy.loginfo("zero time remaining on unknown bay")
00556 self._stop_count += 1
00557 else:
00558 self._stop_count = 0
00559
00560
00561
00562 if self._stop_count > 5:
00563 if self._bay and self._bay.name:
00564 rospy.loginfo("Test done on bay %s; stopping" % self._bay.name)
00565 else:
00566 rospy.loginfo("Test done on unknown bay")
00567 self._record.complete_test()
00568 self.stop_test()
00569 self._enable_controls()
00570
00571 def _status_callback(self, msg):
00572 """
00573 Callback from BAY/test_status topic
00574 """
00575 with self._mutex:
00576 self._status_msg = msg
00577
00578 wx.CallAfter(self._new_msg)
00579
00580 def _new_msg(self):
00581 """
00582 Updates state with new data from test_status
00583 """
00584
00585 if self._bay and self._bay.name:
00586 rospy.loginfo("got status for bay %s" % self._bay.name)
00587 else:
00588 rospy.loginfo("got status for unknown bay")
00589
00590 with self._mutex:
00591 test_level = self._status_msg.test_ok
00592 test_msg = self._status_msg.message
00593
00594 self._last_message_time = rospy.get_time()
00595
00596 self._is_running = (test_level == 0)
00597 self._is_stale = False
00598
00599 self._update_controls(test_level, test_msg)
00600 self.update_test_record()
00601 self.stop_if_done()
00602
00603
00604 def make_launch_script(self, bay, script, local_diag_topic):
00605
00606 os.environ['ROS_NAMESPACE'] = bay.name
00607
00608 launch = '<launch>\n'
00609 launch += '<group ns="%s" >\n' % bay.name
00610
00611
00612
00613 launch += '<remap from="/diagnostics" to="%s" />\n' % local_diag_topic
00614 launch += '<remap from="/tf" to="/%s/tf" />\n' % bay.name
00615
00616
00617
00618 launch += '<machine name="test_host" address="%s" default="true" ' % bay.machine
00619 launch += 'ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" timeout="15" />\n'
00620
00621
00622 launch += '<machine name="localhost" address="localhost" '
00623 launch += 'ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" timeout="20" default="false"/>\n'
00624
00625
00626 launch += '<include file="$(find life_test)/%s" />\n' % script
00627
00628
00629 launch += ' <node machine="localhost" pkg="rosbag" type="rosbag" '
00630 launch += 'args="record -o /hwlog/%s_life_test /diagnostics --split 1000" name="test_logger" />\n' % self._serial
00631
00632
00633 launch += ' <node machine="localhost" pkg="rosbag" type="rosbag" name="mtrace_record" '
00634 launch += 'args="record -o /hwlog/%s_motor_trace -e /%s/motor_trace/.* " />\n' % (self._serial, bay.name)
00635
00636 launch += '</group>\n</launch>'
00637
00638 return launch
00639
00640
00641 def start_stop_test(self, event):
00642 if self.launched:
00643 if not self.stop_test_user():
00644 return
00645 else:
00646 if not self.launch_test():
00647 return
00648
00649 self._update_controls()
00650 self._enable_controls()
00651
00652
00653 def stop_test_user(self):
00654 dialog = wx.MessageDialog(self, 'Are you sure you want to stop this test?', 'Confirm Stop Test', wx.OK|wx.CANCEL)
00655 if dialog.ShowModal() != wx.ID_OK:
00656 return False
00657
00658 self.stop_test()
00659 return True
00660
00661 def _tear_down_test(self):
00662 """
00663 Reset displays and state. Shut down test processes
00664 """
00665
00666 self._launch_button.Enable(False)
00667
00668
00669 self.on_halt_test(None)
00670
00671
00672 self._power_board_text.SetBackgroundColour("White")
00673 self._power_board_text.SetValue("Test Not Running")
00674 self._estop_status.SetBackgroundColour("White")
00675 self._estop_status.SetValue("Test Not Running")
00676 self._machine_text.SetValue("Not running")
00677 self._power_sn_text.SetValue("Not running")
00678 self._power_breaker_text.SetValue("Not running")
00679
00680
00681 if self._bay.board is not None:
00682 if not self._manager.power_disable(self._bay):
00683 wx.MessageBox("Power disable command failed. Unable to command power board", "Power command failed", wx.OK|wx.ICON_ERROR, self)
00684
00685
00686
00687 try:
00688 if self._test_launcher:
00689 self._test_launcher.shutdown()
00690 except Exception, e:
00691 rospy.logerr('Unable to shutdown test')
00692 rospy.logerr(traceback.format_exc())
00693 self.update_test_record(traceback.format_exc())
00694
00695 self._manager.test_stop(self._bay)
00696 self.update_test_record('Shutting down test processes.')
00697
00698
00699 self._is_running = False
00700 self._test_launcher = None
00701 self._bay = None
00702 self._record.set_bay(None)
00703
00704
00705 self._launch_button.Enable(True)
00706 self._update_controls()
00707 self._enable_controls()
00708
00709 def stop_test(self):
00710 if self.launched:
00711 self._tear_down_test()
00712
00713 if self._status_sub:
00714 self._status_sub.unregister()
00715 self._status_sub = None
00716
00717 self._monitor_panel.change_diagnostic_topic('empty')
00718
00719 self._is_running = False
00720
00721 def _check_machine(self, bay):
00722 """
00723 Check the machine is online.
00724
00725 @return True if machine is OK
00726 """
00727 try:
00728 machine_addr = socket.gethostbyname(bay.machine)
00729 except socket.gaierror:
00730 wx.MessageBox('Hostname "%s" (bay "%s") is invalid. The machine may be offline or disconnected.' % (bay.machine, bay.name),
00731 'Test Bay Invalid', wx.OK|wx.ICON_ERROR)
00732 return False
00733
00734
00735 retcode = subprocess.call('ping -c1 -W1 %s > /dev/null' % bay.machine, shell=True)
00736 if retcode != 0:
00737 wx.MessageBox('Cannot contact machine "%s" for bay "%s". It may be offline or disconnected. Check the machine and retry.' % (bay.machine, bay.name),
00738 'Test Bay Unavailable', wx.OK|wx.ICON_ERROR)
00739 return False
00740
00741 return True
00742
00743 def _check_keys(self, bay):
00744 """
00745 Check that machine has valid keys for remote launching
00746
00747 Uses paramiko to make sure it can open a connection to the remote machine. Will open a message box with
00748 error message if it is unable to log in. Returns False if failure, True if OK.
00749 """
00750 ssh = paramiko.SSHClient()
00751
00752
00753 try:
00754 if os.path.isfile('/etc/ssh/ssh_known_hosts'):
00755 ssh.load_system_host_keys('/etc/ssh/ssh_known_hosts')
00756 except IOError:
00757 pass
00758
00759 try:
00760 ssh.load_system_host_keys()
00761 except IOError:
00762 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',
00763 'Launch Error - Known Hosts', wx.OK)
00764
00765
00766 ssh.set_missing_host_key_policy(paramiko.AutoAddPolicy())
00767
00768 try:
00769 ssh.connect(bay.machine, 22, None, timeout=10)
00770 except paramiko.BadHostKeyException:
00771 wx.MessageBox('Unable to verify host key for machine %s. Check authetication with "ssh MACHINE"' % bay.machine,
00772 'Bad Host Key', wx.OK|wx.ICON_ERROR)
00773 return False
00774 except paramiko.AuthenticationException:
00775 wx.MessageBox('Unable to log in to remote machine %s. Authentication failed. Machine may not be configured.' % bay.machine,
00776 'Authentication Failed', wx.OK|wx.ICON_ERROR)
00777 return False
00778 except paramiko.SSHException:
00779 wx.MessageBox('Unable to launch. Unknown server %s. Machine may be invalid.' % bay.machine,
00780 'Unknown Server', wx.OK|wx.ICON_ERROR)
00781 return False
00782 except Exception:
00783 wx.MessageBox('Unable to launch on machine %s. Unknown exception' % bay.machine,
00784 'Unknown Launching Exception', wx.OK|wx.ICON_ERROR)
00785 import traceback
00786 self.update_test_record(traceback.format_exc())
00787 return False
00788
00789 ssh.close()
00790
00791 return True
00792
00793 def _load_bay(self):
00794 """
00795 Checks that the bay is valid, reserves bay, runs power.
00796
00797 @return None if bay invalid
00798 """
00799 bay_name = self._test_bay_ctrl.GetStringSelection()
00800 bay = self._manager.room.get_bay(bay_name)
00801 if bay is None:
00802 wx.MessageBox('Select test bay', 'Select Bay', wx.OK|wx.ICON_ERROR, self)
00803 return None
00804
00805 return bay
00806
00807
00808 def _enable_bay(self):
00809 """
00810 Reserve bay from manager, enable power
00811
00812 @return False if unable to reserve bay or enable power
00813 """
00814 if not self._manager.test_start_check(self._bay, self._serial):
00815 wx.MessageBox('Test bay in use, select again!', 'Test bay in use', wx.OK|wx.ICON_ERROR, self)
00816 return False
00817
00818 if self._bay.board is not None:
00819 if not self._manager.power_run(self._bay):
00820 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)
00821 self._manager.test_stop(self._bay)
00822 return False
00823
00824 return True
00825
00826 def _check_test_ready(self):
00827 """
00828 Check if test has <0 time remaining.
00829
00830 @return False if test has no time left
00831 """
00832 if self._calc_remaining() <= 0:
00833 wx.MessageBox('Test has no allowable time left. Add more hours/minutes and retry.',
00834 'Out of Time', wx.OK|wx.ICON_ERROR, self)
00835 return False
00836 return True
00837
00838 def _confirm_launch(self):
00839 """
00840 Checks with user to make sure test can start.
00841
00842 @return True if user is OK
00843 """
00844 dialog = wx.MessageDialog(self, 'Are you sure you want to launch?', 'Confirm Launch', wx.OK|wx.CANCEL)
00845 ok = dialog.ShowModal() == wx.ID_OK
00846 dialog.Destroy()
00847
00848 return ok
00849
00850 def launch_test(self):
00851 """
00852 Launches test on correct bay
00853
00854 @return False if launch failed or aborted
00855 """
00856
00857 self._launch_button.Enable(False)
00858
00859
00860 if not self._check_test_ready():
00861 self._launch_button.Enable(True)
00862 return False
00863
00864
00865 bay = self._load_bay()
00866 if not bay:
00867 self._launch_button.Enable(True)
00868 return False
00869
00870
00871 if not self._check_machine(bay):
00872 self._launch_button.Enable(True)
00873 return False
00874
00875
00876 if not self._check_keys(bay):
00877 self._launch_button.Enable(True)
00878 return False
00879
00880
00881 if not self._confirm_launch():
00882 self._launch_button.Enable(True)
00883 return False
00884
00885 self._bay = bay
00886 self._record.set_bay(self._bay)
00887
00888
00889 if not self._enable_bay():
00890 self._launch_button.Enable(True)
00891 self._bay = None
00892 self._record.set_bay(None)
00893 return False
00894
00895
00896 self._machine_text.SetValue(self._bay.machine)
00897 if self._bay.board is not None and self._test.needs_power:
00898 self._power_sn_text.SetValue(str(self._bay.board))
00899 self._power_breaker_text.SetValue(str(self._bay.breaker))
00900 self._power_board_text.SetValue("No data")
00901 self._power_board_text.SetBackgroundColour("Light Blue")
00902 self._estop_status.SetValue("No data")
00903 self._estop_status.SetBackgroundColour("Light Blue")
00904 self._power_stat = "No data"
00905 self._estop_stat = False
00906 else:
00907 self._power_sn_text.SetValue("No board")
00908 self._power_breaker_text.SetValue("No breaker")
00909 self._power_board_text.SetValue("No board")
00910 self._power_board_text.SetBackgroundColour("White")
00911 self._estop_status.SetBackgroundColour("White")
00912 self._estop_status.SetValue("No board")
00913
00914 self.update_test_record('Launching test %s on bay %s, machine %s.' % (self._test._name, self._bay.name, self._bay.machine))
00915
00916 sleep(1)
00917
00918 self._last_message_time = rospy.get_time()
00919
00920
00921 local_diag = '/' + self._bay.name + '/diagnostics'
00922
00923
00924 rospy.set_param(self._bay.name, {})
00925 self._test.set_params(self._bay.name)
00926 self._test_launcher = roslaunch_caller.ScriptRoslaunch(
00927 self.make_launch_script(self._bay, self._test.launch_file, local_diag))
00928 try:
00929 self._test_launcher.start()
00930 except Exception, e:
00931 traceback.print_exc()
00932 self.update_test_record('Failed to launch script, caught exception.')
00933 self.update_test_record(traceback.format_exc())
00934 self._tear_down_test()
00935 self._launch_button.Enable(True)
00936
00937 wx.MessageBox('Failed to launch. Check machine for connectivity. See log for error message.', 'Failure to launch', wx.OK|wx.ICON_ERROR, self)
00938 return False
00939
00940
00941 local_status = '/' + str(self._bay.name) + '/test_status'
00942 self._is_running = False
00943 self._monitor_panel.change_diagnostic_topic(local_diag)
00944 self._status_sub = rospy.Subscriber(local_status, TestStatus, self._status_callback)
00945
00946 self._update_controls()
00947 self._enable_controls()
00948 self._launch_button.Enable(True)
00949
00950 return True
00951
00952 def on_halt_test(self, event = None):
00953 """
00954 Calls halt_test service to test monitor
00955 """
00956 try:
00957 self.update_test_record('Pausing test.')
00958 halt_srv = rospy.ServiceProxy(self._bay.name + '/halt_test', Empty)
00959 halt_srv()
00960
00961 return True
00962
00963 except Exception, e:
00964 rospy.logerr('Exception on halt test.\n%s' % traceback.format_exc())
00965
00966 self.update_test_record('Unable to reset test, caught exception: %s' % e)
00967 return False
00968
00969 def on_reset_test(self, event = None):
00970 """
00971 Calls reset_test service to test monitor
00972 """
00973 try:
00974 self.update_test_record('Resetting test.')
00975 reset = rospy.ServiceProxy(self._bay.name + '/reset_test', Empty)
00976 reset()
00977
00978 return True
00979
00980 except Exception, e:
00981 rospy.logerr('Exception on reset test.\n%s' % traceback.format_exc())
00982 self.update_test_record('Unable to reset test, caught exception: %s' % e)
00983 return False
00984
00985
00986 def record_test_log(self):
00987 """
00988 Called when test is closing down.
00989 """
00990 self._record.load_attachments(self._manager.invent_client)
00991
00992 def on_invent_timer(self, event):
00993 """
00994 Update inventory system with a note on progress every 10 minutes
00995 """
00996 self._record.update_invent(self._manager.invent_client)
00997
00998
00999