status_panel.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 #
00003 # Software License Agreement (BSD License)
00004 #
00005 # Copyright (c) 2009, Willow Garage, Inc.
00006 # All rights reserved.
00007 #
00008 # Redistribution and use in source and binary forms, with or without
00009 # modification, are permitted provided that the following conditions
00010 # are met:
00011 #
00012 #  * Redistributions of source code must retain the above copyright
00013 #    notice, this list of conditions and the following disclaimer.
00014 #  * Redistributions in binary form must reproduce the above
00015 #    copyright notice, this list of conditions and the following
00016 #    disclaimer in the documentation and/or other materials provided
00017 #    with the distribution.
00018 #  * Neither the name of the Willow Garage nor the names of its
00019 #    contributors may be used to endorse or promote products derived
00020 #    from this software without specific prior written permission.
00021 #
00022 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033 # POSSIBILITY OF SUCH DAMAGE.
00034 
00035 # Author: Kevin Watts
00036 
00037 PKG = 'life_test'
00038 import roslib
00039 roslib.load_manifest(PKG)
00040 
00041 import wx
00042 from wx import xrc
00043 import rospy
00044 
00045 import threading
00046 import math
00047 import os
00048 
00049 from pr2_self_test_msgs.msg import TestInfoArray, TestInfo
00050 
00051 def get_duration_str(duration):
00052     hrs = max(math.floor(duration / 3600), 0)
00053     min = max(math.floor(duration / 6), 0) / 10 - hrs * 60
00054     
00055     return "%dhr, %.1fm" % (hrs, min)
00056 
00057 ##\brief Displays test status, including bay, power, estop, elapsed time
00058 class TestStatusPanel(wx.Panel):
00059     def __init__(self, parent):
00060         wx.Panel.__init__(self, parent, -1)
00061 
00062         self._frame = parent
00063         
00064         xrc_path = os.path.join(roslib.packages.get_pkg_dir(PKG), 'xrc/gui.xrc')
00065         self._panel = xrc.XmlResource(xrc_path).LoadPanel(self, 'status_panel')
00066         self._bay_status = xrc.XRCCTRL(self._panel, 'bay_status')
00067         self._power_status = xrc.XRCCTRL(self._panel, 'power_status')
00068         self._estop_status = xrc.XRCCTRL(self._panel, 'estop_status')
00069         self._test_name_text = xrc.XRCCTRL(self._panel, 'test_name_text')
00070         self._serial_text = xrc.XRCCTRL(self._panel, 'serial_text')
00071         self._elapsed_text = xrc.XRCCTRL(self._panel, 'elapsed_text')
00072         self._machine_text = xrc.XRCCTRL(self._panel, 'machine_text')
00073 
00074         #self._close_button = xrc.XRCCTRL(self._panel, 'close_button')
00075         #self._close_button.Bind(wx.EVT_BUTTON, self.on_close)
00076         #self._close_button.Enable(False)
00077 
00078         self._bay_status.SetValue("Bay: None")
00079         self._power_status.SetValue("No Power Data")
00080         self._estop_status.SetValue("No Power Data")
00081         self._test_name_text.SetValue("No Test")
00082         self._serial_text.SetValue("No Test")
00083         self._elapsed_text.SetValue("No Data")
00084         self._machine_text.SetValue("Machine: None")
00085 
00086         self._serial = None
00087 
00088     def on_close(self, event):
00089         self._frame.close_tab(self._serial)
00090 
00091     def get_test_name(self):
00092         return self._test_name_text.GetValue()
00093 
00094     def get_elapsed(self):
00095         return self._elapsed
00096 
00097     def set_stale(self):
00098         self._bay_status.SetBackgroundColour("Light Blue")
00099         self._bay_status.SetValue("Stale")
00100 
00101         self._power_status.SetBackgroundColour("Light Blue")
00102         self._estop_status.SetBackgroundColour("Light Blue")
00103         self._elapsed_text.SetBackgroundColour("Light Blue")
00104 
00105     ##\brief Update display with new status message
00106     def update(self, msg):
00107         if msg.test_status == -1:
00108             self._bay_status.SetBackgroundColour("White")
00109             self._bay_status.SetValue("OFF")
00110             
00111         elif msg.test_status == 127:
00112             self._bay_status.SetBackgroundColour("White")
00113             self._bay_status.SetValue("N/A")
00114         elif msg.test_status == 0:
00115             self._bay_status.SetBackgroundColour("Light Green")
00116             self._bay_status.SetValue(msg.bay_name)
00117         elif msg.test_status == 1:
00118             self._bay_status.SetBackgroundColour("Orange")
00119             self._bay_status.SetValue(msg.bay_name)
00120         elif msg.test_status == 2:
00121             self._bay_status.SetBackgroundColour("Red")
00122             self._bay_status.SetValue(msg.bay_name)
00123         elif msg.test_status == 3 or msg.test_status == 4:
00124             self._bay_status.SetBackgroundColour("Light Blue")
00125             self._bay_status.SetValue(msg.bay_name)
00126 
00127         if msg.board == 0:
00128             self._power_status.SetValue("No power board")
00129             self._power_status.SetBackgroundColour("White")
00130             self._estop_status.SetValue("No power board")
00131             self._estop_status.SetBackgroundColour("While")
00132         else:
00133             if msg.power_status == "No data":
00134                 self._power_status.SetBackgroundColour("Light Blue")
00135                 self._power_status.SetValue("No data - %d #%d" % (msg.board, msg.breaker))
00136             elif msg.power_status == "Stale":
00137                 self._power_status.SetBackgroundColour("Light Blue")
00138                 self._power_status.SetValue("Stale - %d #%d" % (msg.board, msg.breaker))
00139             elif msg.power_status == "Standby":
00140                 self._power_status.SetBackgroundColour("Orange")
00141                 self._power_status.SetValue("Standby - %d #%d" % (msg.board, msg.breaker))
00142             elif msg.power_status == "On":
00143                 self._power_status.SetBackgroundColour("Light Green")
00144                 self._power_status.SetValue("On - %d #%d" % (msg.board, msg.breaker))
00145             else:
00146                 self._power_status.SetBackgroundColour("Red")
00147                 self._power_status.SetValue("Disabled - %d #%d" % (msg.board, msg.breaker))
00148             if msg.estop == 0 and msg.power_status != "Stale" and msg.power_status != "No data":
00149                 self._estop_status.SetBackgroundColour("Red")
00150                 self._estop_status.SetValue("E-Stop Hit")
00151             elif msg.estop == 0:
00152                 self._estop_status.SetBackgroundColour("Light Blue")
00153                 self._estop_status.SetValue("No E-Stop Data")
00154             else:
00155                 self._estop_status.SetBackgroundColour("Light Green")
00156                 self._estop_status.SetValue("E-Stop OK")
00157         
00158         self._test_name_text.SetValue(msg.test_name)
00159         self._serial = msg.serial
00160         self._serial_text.SetValue(self._serial)
00161 
00162         self._elapsed = msg.elapsed
00163         self._elapsed_text.SetBackgroundColour("White")
00164         self._elapsed_text.SetValue(get_duration_str(self._elapsed))
00165         if msg.machine == "":
00166             self._machine_text.SetValue("Not launched")
00167         else:
00168             self._machine_text.SetValue("Machine: %s" % msg.machine)
00169 
00170 ##\brief Holds status panels in scrolled window
00171 ##
00172 ## Subscribes to 'test_info'/TestInfoArray and creates/updates status panels
00173 ## from information. 
00174 class TestContainerStatusPanel(wx.Panel):
00175     def __init__(self, parent):
00176         wx.Panel.__init__(self, parent)
00177 
00178         self._mutex = threading.Lock()
00179         
00180         xrc_path = os.path.join(roslib.packages.get_pkg_dir(PKG), 'xrc/gui.xrc')
00181         
00182         self._info_sub = rospy.Subscriber('test_info', TestInfoArray, self.cb)
00183         
00184         self._panel = xrc.XmlResource(xrc_path).LoadPanel(self, 'status_container_panel')
00185         self._sizer = wx.BoxSizer(wx.VERTICAL)
00186         self._sizer.Add(self._panel, 1, wx.EXPAND)
00187         self.SetSizer(self._sizer)
00188         self.Layout()
00189 
00190         self._scrolled_window = xrc.XRCCTRL(self._panel, 'scrolled_window')
00191         self._scrolled_sizer = wx.BoxSizer(wx.VERTICAL)
00192         self._scrolled_window.SetSizer(self._scrolled_sizer)
00193         self._scrolled_window.SetScrollRate(0, 20)
00194         
00195         self._status_panels = {}
00196         
00197         # Shows blue if we're stale
00198         self._timer = wx.Timer(self)
00199         self.Bind(wx.EVT_TIMER, self.on_timer)
00200         self._timer.Start(1000)
00201 
00202         self.timeout = 5
00203         self.last_message_time = 0
00204 
00205     def on_timer(self, event):
00206         if rospy.get_time() - self.last_message_time < self.timeout:
00207             return
00208 
00209         for serial, panel in self._status_panels.iteritems():
00210             panel.set_stale()
00211 
00212     def close_tab(self, serial):
00213         if not self._status_panels.has_key(serial):
00214             return
00215 
00216         print 'Deleting panel %s' % serial
00217         panel = self._status_panels[serial]
00218         if self._scrolled_sizer.Detach(panel):
00219             print 'detach ok'
00220             self._scrolled_sizer.Layout()
00221         else:
00222             print 'Not detached'
00223         
00224         del self._status_panels[serial]
00225 
00226     def cb(self, msg):
00227         self._mutex.acquire()
00228         self.msg = msg
00229         self._mutex.release()
00230         wx.CallAfter(self.update)
00231 
00232     def update(self):
00233         self._mutex.acquire()
00234         self.last_message_time = rospy.get_time()
00235         serials = self._status_panels.keys()
00236 
00237         for test_info in self.msg.data:
00238             if not self._status_panels.has_key(test_info.serial):
00239                 stat_panel = TestStatusPanel(self)
00240                 stat_panel.SetSize(wx.Size(600, 160))
00241                 self._status_panels[test_info.serial] = stat_panel
00242                 self._scrolled_sizer.Add(stat_panel, 0, wx.EXPAND)
00243                 self._scrolled_sizer.Layout()
00244                 serials.append(test_info.serial)
00245             
00246             self._status_panels[test_info.serial].update(test_info)
00247             
00248             idx = serials.index(test_info.serial)
00249             serials.pop(idx)
00250 
00251         ## Update panels that have closed
00252         for srl in serials:
00253             panel = self._status_panels[srl]
00254 
00255             srl_info = TestInfo()
00256             srl_info.serial = srl
00257             srl_info.test_status = -1
00258             srl_info.board = 0
00259             srl_info.test_name = panel.get_test_name()
00260             srl_info.elapsed = panel.get_elapsed()
00261             srl_info.machine = "None"
00262             
00263             panel.update(srl_info)
00264             
00265         self._mutex.release()
00266         
00267         ## Todo - allow delete used panels
00268         ## put into test manager
00269         ## Add last message field to GUI display
00270 


life_test
Author(s): Kevin Watts
autogenerated on Sat Dec 28 2013 17:56:37