$search
00001 # Software License Agreement (BSD License) 00002 # 00003 # Copyright (c) 2008, Willow Garage, Inc. 00004 # All rights reserved. 00005 # 00006 # Redistribution and use in source and binary forms, with or without 00007 # modification, are permitted provided that the following conditions 00008 # are met: 00009 # 00010 # * Redistributions of source code must retain the above copyright 00011 # notice, this list of conditions and the following disclaimer. 00012 # * Redistributions in binary form must reproduce the above 00013 # copyright notice, this list of conditions and the following 00014 # disclaimer in the documentation and/or other materials provided 00015 # with the distribution. 00016 # * Neither the name of the Willow Garage nor the names of its 00017 # contributors may be used to endorse or promote products derived 00018 # from this software without specific prior written permission. 00019 # 00020 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00021 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00022 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00023 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00024 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00025 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00026 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00027 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00028 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00029 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00030 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00031 # POSSIBILITY OF SUCH DAMAGE. 00032 00033 import roslib; roslib.load_manifest('generic_dashboard') 00034 import rospy 00035 import wx 00036 from status_control import * 00037 from os import path 00038 import robot_monitor 00039 from robot_monitor.robot_monitor_panel import RobotMonitorPanel 00040 from generic_control import GenericControl 00041 00042 class DiagnosticsFrame(wx.Frame): 00043 def __init__(self, parent, id, title): 00044 wx.Frame.__init__(self, parent, id, title, wx.DefaultPosition, wx.Size(400, 600)) 00045 00046 self.Bind(wx.EVT_CLOSE, self.on_close) 00047 00048 self._diagnostics_panel = RobotMonitorPanel(self) 00049 00050 def on_close(self, evt): 00051 self.Hide() 00052 00053 class DiagnosticsControl(StatusControl): 00054 def __init__(self, parent): 00055 StatusControl.__init__(self, parent, path.join(roslib.packages.get_pkg_dir('generic_dashboard'), "icons/"), 00056 'diag', True, {'stale': 'grey', 'ok': 'green', 'warn': 'yellow', 'error': 'red'}, 'stale') 00057 self.SetToolTip(wx.ToolTip("Diagnostics")) 00058 00059 self._diagnostics_frame = DiagnosticsFrame(parent, wx.ID_ANY, "Diagnostics") 00060 self._diagnostics_frame.Hide() 00061 self._diagnostics_frame.Center() 00062 self.Bind(wx.EVT_BUTTON, self.on_diagnostics_clicked) 00063 00064 def on_diagnostics_clicked(self, evt): 00065 self._diagnostics_frame.Show() 00066 self._diagnostics_frame.Raise() 00067 00068 def update(self): 00069 level = self._diagnostics_frame._diagnostics_panel.get_top_level_state() 00070 if (level == -1 or level == 3): 00071 if (self.set_status('stale')): 00072 self.SetToolTip(wx.ToolTip("Diagnostics: Stale")) 00073 elif (level >= 2): 00074 if (self.set_status('error')): 00075 self.SetToolTip(wx.ToolTip("Diagnostics: Error")) 00076 elif (level == 1): 00077 if (self.set_status('warn')): 00078 self.SetToolTip(wx.ToolTip("Diagnostics: Warning")) 00079 else: 00080 if (self.set_status('ok')): 00081 self.SetToolTip(wx.ToolTip("Diagnostics: OK")) 00082 00083 self.Refresh()