power_state_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('turtlebot_dashboard')
00035 import rospy
00036 import wx
00037 
00038 from os import path
00039 
00040 def non_zero(value):
00041   if value < 0.00001 and value > -0.00001:
00042     return 0.00001
00043   return value
00044   
00045 
00046 class PowerStateControl(wx.Window):
00047   def __init__(self, parent, id, icons_path):
00048     wx.Window.__init__(self, parent, id, wx.DefaultPosition, wx.Size(60, 32))
00049     
00050     self._power_consumption = 0.0
00051     self._pct = 0.0
00052     self._cap = 2.7
00053     self._char_cap = 2.7
00054     self._time_remaining = 0.0
00055     self._ac_present = 0.0
00056     
00057     self._left_bitmap = wx.Bitmap(path.join(icons_path, "battery-minus.png"), wx.BITMAP_TYPE_PNG)
00058     self._right_bitmap = wx.Bitmap(path.join(icons_path, "battery-plus.png"), wx.BITMAP_TYPE_PNG)
00059     self._plug_bitmap = wx.Bitmap(path.join(icons_path, "battery-charging.png"), wx.BITMAP_TYPE_PNG)
00060     self._background_bitmap = wx.Bitmap(path.join(icons_path, "battery-background.png"), wx.BITMAP_TYPE_PNG)
00061     self._green = wx.Bitmap(path.join(icons_path, "battery-green-bar.png"), wx.BITMAP_TYPE_PNG)
00062     self._yellow = wx.Bitmap(path.join(icons_path, "battery-yellow-bar.png"), wx.BITMAP_TYPE_PNG)
00063     self._red = wx.Bitmap(path.join(icons_path, "battery-red-bar.png"), wx.BITMAP_TYPE_PNG)
00064     
00065     self.SetSize(wx.Size(self._left_bitmap.GetWidth() + self._right_bitmap.GetWidth() + self._background_bitmap.GetWidth(), 32))
00066     
00067     self._start_x = self._left_bitmap.GetWidth()
00068     self._end_x = self.GetSize().x - self._right_bitmap.GetWidth()
00069     self._width = self._end_x - self._start_x
00070     
00071     self._plugged_in = False
00072     
00073     self.Bind(wx.EVT_PAINT, self.on_paint)
00074 
00075   def on_paint(self, evt):
00076     dc = wx.BufferedPaintDC(self)
00077 
00078     dc.SetBackground(wx.Brush(self.GetBackgroundColour()))
00079     dc.Clear()
00080  
00081     w = self.GetSize().GetWidth()
00082     h = self._left_bitmap.GetHeight()
00083     
00084     color_bitmap = None
00085     if (self._pct > 0.5):
00086       color_bitmap = self._green
00087     elif (self._pct > 0.3):
00088       color_bitmap = self._yellow
00089     else:
00090       color_bitmap = self._red
00091     
00092     dc.DrawBitmap(self._background_bitmap, self._start_x, 0, True)
00093     
00094     color_image = color_bitmap.ConvertToImage()
00095     scaled_color_image = color_image.Rescale(round(self._width * self._pct), color_bitmap.GetHeight())
00096     color_bitmap = wx.BitmapFromImage(scaled_color_image)
00097     dc.DrawBitmap(color_bitmap, self._start_x, 0, True)
00098     dc.DrawBitmap(self._left_bitmap, 0, 0, True)
00099     dc.DrawBitmap(self._right_bitmap, self._end_x, 0, True)
00100     
00101     if (self._plugged_in):
00102       dc.DrawBitmap(self._plug_bitmap, 
00103                     (self._start_x + self._width) / 2.0 - (self._plug_bitmap.GetWidth() / 2.0), 
00104                     self.GetSize().GetHeight() / 2.0 - (self._plug_bitmap.GetHeight() / 2.0))
00105       
00106       
00107   def set_power_state(self, msg):
00108     last_pct = self._pct
00109     last_plugged_in = self._plugged_in
00110     last_time_remaining = self._time_remaining
00111     self._char_cap = 0.8*self._char_cap +0.2*float(msg['Charge (Ah)'])     
00112     #make sure that battery percentage is not greater than 100%
00113     if self._char_cap < float(msg['Capacity (Ah)']):
00114       self._cap = float(msg['Capacity (Ah)'])
00115     else: 
00116       self._cap = self._char_cap
00117 
00118     self._power_consumption = float(msg['Current (A)'])*float(msg['Voltage (V)'])
00119     #determine if we're charging or discharging
00120     if float(msg['Current (A)'])<0:
00121       tmp = (float(msg['Charge (Ah)'])/non_zero(float(msg['Current (A)'])))*60.0
00122     else:
00123       tmp = ((float(msg['Charge (Ah)'])-self._cap)/non_zero(float(msg['Current (A)'])))*60.0
00124 
00125     self._time_remaining = 0.8*self._time_remaining + 0.2*tmp
00126   
00127     self._pct = float(msg['Charge (Ah)'])/self._cap
00128 
00129     if self._pct == 1 and float(msg['Current (A)']) == 0:
00130         self._plugged_in = True
00131     else:
00132         self._plugged_in = (float(msg['Current (A)'])>0)
00133     
00134     if (last_pct != self._pct or last_plugged_in != self._plugged_in or last_time_remaining != self._time_remaining):
00135         drain_str = "remaining"
00136         if (self._plugged_in):
00137             drain_str = "to full charge"
00138         self.SetToolTip(wx.ToolTip("Battery: %.2f%% (%d minutes %s)"%(self._pct * 100.0, abs(self._time_remaining), drain_str)))
00139     self.Refresh()
00140     
00141   def set_stale(self):
00142     self._plugged_in = 0
00143     self._pct = 0
00144     self._time_remaining = 0.0
00145     self._power_consumption = 0
00146     self.SetToolTip(wx.ToolTip("Battery: Stale"))
00147     
00148     self.Refresh()


turtlebot_dashboard
Author(s): Melonee Wise
autogenerated on Mon Dec 2 2013 12:18:09