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 import roslib
00034 roslib.load_manifest('lwr_dashboard')
00035 
00036 import wx
00037 
00038 from os import path
00039 
00040 class StatusControl(wx.Window):
00041   def __init__(self, parent, id, icons_path, base_name, toggleable):
00042     wx.Window.__init__(self, parent, id)
00043     self.SetSize(wx.Size(40, 40))
00044     
00045     base_bitmap = wx.Bitmap(path.join(icons_path, "%s.png" % base_name), wx.BITMAP_TYPE_PNG);
00046     
00047     self._ok    = (base_bitmap.GetSubBitmap(wx.Rect(  0,  0, 40, 40)),
00048                    base_bitmap.GetSubBitmap(wx.Rect(  0, 40, 40, 40)))
00049     self._warn  = (base_bitmap.GetSubBitmap(wx.Rect( 40,  0, 40, 40)),
00050                    base_bitmap.GetSubBitmap(wx.Rect( 40, 40, 40, 40)))
00051     self._error = (base_bitmap.GetSubBitmap(wx.Rect( 80,  0, 40, 40)),
00052                    base_bitmap.GetSubBitmap(wx.Rect( 80, 40, 40, 40)))
00053     self._stale = (base_bitmap.GetSubBitmap(wx.Rect(120,  0, 40, 40)),
00054                    base_bitmap.GetSubBitmap(wx.Rect(120, 40, 40, 40)))
00055     
00056     self._color = None
00057     self.set_stale()
00058     
00059     self.Bind(wx.EVT_PAINT, self.on_paint)
00060     self.Bind(wx.EVT_LEFT_UP, self.on_left_up)
00061     self.Bind(wx.EVT_LEFT_DOWN, self.on_left_down)
00062     self.Bind(wx.EVT_LEAVE_WINDOW, self.on_leave_window)
00063     self.Bind(wx.EVT_ENTER_WINDOW, self.on_enter_window)
00064     
00065     self._toggled = False
00066     self._left_down = False
00067     
00068   def toggle(self, tog):
00069     if (self._toggled == tog):
00070         return False
00071     
00072     self._toggled = tog
00073     self.Refresh()
00074     
00075     return True
00076 
00077   def on_left_down(self, evt):
00078     self.toggle(True)
00079     self._left_down = True
00080     self.Refresh()
00081 
00082   def on_left_up(self, evt):
00083     self.toggle(False)
00084     self._left_down = False
00085     x = evt.GetX()
00086     y = evt.GetY()
00087     if (x >= 0 and y >= 0 and x < self.GetSize().GetWidth() and y < self.GetSize().GetHeight()):
00088       event = wx.CommandEvent(wx.EVT_BUTTON._getEvtType(), self.GetId())
00089       wx.PostEvent(self, event)
00090       
00091     self.Refresh()
00092 
00093   def on_leave_window(self, evt):
00094     self.toggle(False)
00095     self.Refresh()
00096     
00097   def on_enter_window(self, evt):
00098     if (self._left_down):
00099       self.toggle(True)
00100       
00101     self.Refresh()
00102 
00103   def on_paint(self, evt):
00104     dc = wx.BufferedPaintDC(self)
00105     dc.SetBackground(wx.Brush(self.GetBackgroundColour()))
00106     dc.Clear()
00107     
00108     size = self.GetSize();
00109         
00110     bitmap = None
00111     if (self._toggled):
00112       bitmap = self._color[1]
00113     else:
00114       bitmap = self._color[0]
00115     
00116     offset_x = (size.GetWidth() - bitmap.GetWidth()) / 2.0
00117     offset_y = (size.GetHeight() - bitmap.GetHeight()) / 2.0
00118     
00119     dc.DrawBitmap(bitmap, offset_x, offset_y, True)
00120 
00121   def set_ok(self):
00122     if (self._color == self._ok):
00123         return False
00124     
00125     self._color = self._ok
00126     self.update()
00127     
00128     return True
00129     
00130   def set_warn(self):
00131     if (self._color == self._warn):
00132         return False
00133       
00134     self._color = self._warn
00135     self.update()
00136     
00137     return True
00138     
00139   def set_error(self):
00140     if (self._color == self._error):
00141         return False
00142       
00143     self._color = self._error
00144     self.update()
00145     
00146     return True
00147     
00148   def set_stale(self):
00149     if (self._color == self._stale):
00150         return False
00151       
00152     self._color = self._stale
00153     self.update()
00154     
00155     return True
00156     
00157   def update(self):
00158     self.Refresh()
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


lwr_dashboard
Author(s): Maciej StefaƄczyk
autogenerated on Thu Nov 14 2013 11:53:51