status_control.py
Go to the documentation of this file.
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 
00034 #       modifications to status_control.py to work with p2os_dashboard
00035 #       Copyright (C) 2010  David Feil-Seifer [dfseifer@usc.edu], Edward T. Kaszubski [kaszubsk@usc.edu]
00036 #
00037 #       This program is free software; you can redistribute it and/or modify
00038 #       it under the terms of the GNU General Public License as published by
00039 #       the Free Software Foundation; either version 2 of the License, or
00040 #       (at your option) any later version.
00041 #       
00042 #       This program is distributed in the hope that it will be useful,
00043 #       but WITHOUT ANY WARRANTY; without even the implied warranty of
00044 #       MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00045 #       GNU General Public License for more details.
00046 #       
00047 #       You should have received a copy of the GNU General Public License
00048 #       along with this program; if not, write to the Free Software
00049 #       Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
00050 #       MA 02110-1301, USA.
00051 
00052 import roslib
00053 roslib.load_manifest('p2os_dashboard')
00054 
00055 import wx
00056 
00057 from os import path
00058 
00059 class StatusControl(wx.Window):
00060   def __init__(self, parent, id, icons_path, base_name, toggleable):
00061     wx.Window.__init__(self, parent, id)
00062     self.SetSize(wx.Size(32, 32))
00063     
00064     if (toggleable):
00065       self._ok = (wx.Bitmap(path.join(icons_path, "%s-green-untoggled.png"%(base_name)), wx.BITMAP_TYPE_PNG), 
00066                   wx.Bitmap(path.join(icons_path, "%s-green-toggled.png"%(base_name)), wx.BITMAP_TYPE_PNG))
00067       self._warn = (wx.Bitmap(path.join(icons_path, "%s-yellow-untoggled.png"%(base_name)), wx.BITMAP_TYPE_PNG), 
00068                     wx.Bitmap(path.join(icons_path, "%s-yellow-toggled.png"%(base_name)), wx.BITMAP_TYPE_PNG))
00069       self._error = (wx.Bitmap(path.join(icons_path, "%s-red-untoggled.png"%(base_name)), wx.BITMAP_TYPE_PNG), 
00070                    wx.Bitmap(path.join(icons_path, "%s-red-toggled.png"%(base_name)), wx.BITMAP_TYPE_PNG))
00071       self._stale = (wx.Bitmap(path.join(icons_path, "%s-grey-untoggled.png"%(base_name)), wx.BITMAP_TYPE_PNG), 
00072                      wx.Bitmap(path.join(icons_path, "%s-grey-toggled.png"%(base_name)), wx.BITMAP_TYPE_PNG))
00073     else:
00074       ok = wx.Bitmap(path.join(icons_path, "%s-green.png"%(base_name)), wx.BITMAP_TYPE_PNG)
00075       warn = wx.Bitmap(path.join(icons_path, "%s-yellow.png"%(base_name)), wx.BITMAP_TYPE_PNG)
00076       error = wx.Bitmap(path.join(icons_path, "%s-red.png"%(base_name)), wx.BITMAP_TYPE_PNG)
00077       stale = wx.Bitmap(path.join(icons_path, "%s-grey.png"%(base_name)), wx.BITMAP_TYPE_PNG)
00078       self._ok = (ok, ok)
00079       self._warn = (warn, warn)
00080       self._error = (error, error)
00081       self._stale = (stale, stale)
00082     
00083     self._color = None
00084     self.set_stale()
00085     
00086     self.Bind(wx.EVT_PAINT, self.on_paint)
00087     self.Bind(wx.EVT_LEFT_UP, self.on_left_up)
00088     self.Bind(wx.EVT_LEFT_DOWN, self.on_left_down)
00089     self.Bind(wx.EVT_LEAVE_WINDOW, self.on_leave_window)
00090     self.Bind(wx.EVT_ENTER_WINDOW, self.on_enter_window)
00091     
00092     self._toggled = False
00093     self._left_down = False
00094     
00095   def toggle(self, tog):
00096     if (self._toggled == tog):
00097         return False
00098     
00099     self._toggled = tog
00100     self.Refresh()
00101     
00102     return True
00103 
00104   def on_left_down(self, evt):
00105     self.toggle(True)
00106     self._left_down = True
00107     self.Refresh()
00108 
00109   def on_left_up(self, evt):
00110     self.toggle(False)
00111     self._left_down = False
00112     x = evt.GetX()
00113     y = evt.GetY()
00114     if (x >= 0 and y >= 0 and x < self.GetSize().GetWidth() and y < self.GetSize().GetHeight()):
00115       event = wx.CommandEvent(wx.EVT_BUTTON._getEvtType(), self.GetId())
00116       wx.PostEvent(self, event)
00117       
00118     self.Refresh()
00119 
00120   def on_leave_window(self, evt):
00121     self.toggle(False)
00122     self.Refresh()
00123     
00124   def on_enter_window(self, evt):
00125     if (self._left_down):
00126       self.toggle(True)
00127       
00128     self.Refresh()
00129 
00130   def on_paint(self, evt):
00131     dc = wx.BufferedPaintDC(self)
00132     dc.SetBackground(wx.Brush(self.GetBackgroundColour()))
00133     dc.Clear()
00134     
00135     size = self.GetSize();
00136     
00137     bitmap = None
00138     if (self._toggled):
00139       bitmap = self._color[1]
00140     else:
00141       bitmap = self._color[0]
00142     
00143     dc.DrawBitmap(bitmap, (size.GetWidth() - bitmap.GetWidth()) / 2.0, (size.GetHeight() - bitmap.GetHeight()) / 2.0, True)
00144 
00145   def set_ok(self):
00146     if (self._color == self._ok):
00147         return False
00148     
00149     self._color = self._ok
00150     self.update()
00151     
00152     return True
00153     
00154   def set_warn(self):
00155     if (self._color == self._warn):
00156         return False
00157       
00158     self._color = self._warn
00159     self.update()
00160     
00161     return True
00162     
00163   def set_error(self):
00164     if (self._color == self._error):
00165         return False
00166       
00167     self._color = self._error
00168     self.update()
00169     
00170     return True
00171     
00172   def set_stale(self):
00173     if (self._color == self._stale):
00174         return False
00175       
00176     self._color = self._stale
00177     self.update()
00178     
00179     return True
00180     
00181   def update(self):
00182     self.Refresh()


p2os_dashboard
Author(s): David Feil-Seifer (dfseifer@usc.edu)
autogenerated on Thu Jun 12 2014 10:30:37