00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033 import roslib
00034 roslib.load_manifest('turtlebot_dashboard')
00035
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
00052 self._cap = 0
00053 self._char_cap = 0
00054 self._time_remaining = 0.0
00055 self._ac_present = 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
00112 self._char_cap = 0.95*self._char_cap +0.05*float(msg['Charge (Ah)'])
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 self._power_consumption = float(msg['Current (A)'])*float(msg['Voltage (V)'])
00118 self._time_remaining = 0.9*self._time_remaining + 0.1*((float(msg['Charge (Ah)'])-self._cap)/non_zero(float(msg['Current (A)'])))*60.0
00119 self._pct = float(msg['Charge (Ah)'])/self._cap
00120 self._plugged_in = (float(msg['Current (A)'])>0)
00121
00122 if (last_pct != self._pct or last_plugged_in != self._plugged_in or last_time_remaining != self._time_remaining):
00123 drain_str = "remaining"
00124 if (self._plugged_in):
00125 drain_str = "to full charge"
00126 self.SetToolTip(wx.ToolTip("Battery: %.2f%% (%d minutes %s)"%(self._pct * 100.0, abs(self._time_remaining), drain_str)))
00127 self.Refresh()
00128
00129 def set_stale(self):
00130 self._plugged_in = 0
00131 self._pct = 0
00132 self._time_remaining = 0.0
00133 self._power_consumption = 0
00134 self.SetToolTip(wx.ToolTip("Battery: Stale"))
00135
00136 self.Refresh()