$search
00001 00002 #!/usr/bin/env python 00003 # Software License Agreement (BSD License) 00004 # 00005 # Copyright (c) 2008, Willow Garage, Inc. 00006 # All rights reserved. 00007 # 00008 # Redistribution and use in source and binary forms, with or without 00009 # modification, are permitted provided that the following conditions 00010 # are met: 00011 # 00012 # * Redistributions of source code must retain the above copyright 00013 # notice, this list of conditions and the following disclaimer. 00014 # * Redistributions in binary form must reproduce the above 00015 # copyright notice, this list of conditions and the following 00016 # disclaimer in the documentation and/or other materials provided 00017 # with the distribution. 00018 # * Neither the name of the Willow Garage nor the names of its 00019 # contributors may be used to endorse or promote products derived 00020 # from this software without specific prior written permission. 00021 # 00022 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00023 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00024 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00025 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00026 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00027 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00028 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00029 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00030 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00031 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00032 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00033 # POSSIBILITY OF SUCH DAMAGE. 00034 # 00035 00036 from __future__ import division 00037 PKG = 'ocean_battery_driver' 00038 00039 import roslib 00040 roslib.load_manifest(PKG) 00041 00042 import sys 00043 import rospy 00044 from pr2_msgs.msg import PowerState 00045 00046 00047 import wx 00048 from wx import xrc 00049 00050 import threading, time 00051 00052 class BatteryPanel(wx.Panel): 00053 def __init__(self, parent): 00054 wx.Panel.__init__(self, parent, wx.ID_ANY) 00055 00056 self._mutex = threading.Lock() 00057 00058 xrc_path = roslib.packages.get_pkg_dir(PKG) + '/ui/battery_status_panel.xrc' 00059 00060 self._xrc = xrc.XmlResource(xrc_path) 00061 self._real_panel = self._xrc.LoadPanel(self, 'BatteryStatusPanel') 00062 sizer = wx.BoxSizer(wx.VERTICAL) 00063 sizer.Add(self._real_panel, 1, wx.EXPAND) 00064 self.SetSizer(sizer) 00065 00066 rospy.Subscriber("power_state", PowerState, self.message_callback) 00067 00068 self.power_text = xrc.XRCCTRL(self._real_panel, 'm_powerField') 00069 self.time_field = xrc.XRCCTRL(self._real_panel, 'm_timeField') 00070 self.status_text = xrc.XRCCTRL(self._real_panel, 'm_statusField') 00071 self.capacity_gauge = xrc.XRCCTRL(self._real_panel, 'm_capacityGauge') 00072 self.capacity_text = xrc.XRCCTRL(self._real_panel, 'm_capacityText') 00073 00074 self.power_text.SetEditable(False) 00075 self.time_field.SetEditable(False) 00076 self.status_text.SetEditable(False) 00077 self.capacity_text.SetEditable(False) 00078 00079 # Start a timer to check for timeout 00080 self.timeout_interval = 10 00081 self.last_message_time = rospy.get_time() 00082 self.timer = wx.Timer(self, 1) 00083 self.Bind(wx.EVT_TIMER, self.on_timer, self.timer) 00084 self.start_timer() 00085 00086 self._messages = [] 00087 00088 def message_callback(self, message): 00089 self._mutex.acquire() 00090 00091 self._messages.append(message) 00092 self.last_message_time = rospy.get_time() 00093 00094 self._mutex.release() 00095 00096 wx.CallAfter(self.new_message) 00097 00098 def new_message(self): 00099 self._mutex.acquire() 00100 for message in self._messages: 00101 self.start_timer() 00102 self.power_text.Enable() 00103 self.time_field.Enable() 00104 self.status_text.Enable() 00105 self.capacity_text.Enable() 00106 self.status_text.SetValue('%s'%message.prediction_method) 00107 self.power_text.SetValue('%.2f Watts'%message.power_consumption) 00108 self.capacity_gauge.SetValue(message.relative_capacity) 00109 self.capacity_text.SetValue('%d%%'%message.relative_capacity) 00110 time_remaining = message.time_remaining.to_sec() / 60 00111 if message.AC_present > 0: 00112 self.time_field.SetValue('%u minutes to full'%(time_remaining)) 00113 self.time_field.SetBackgroundColour("White") 00114 else: 00115 self.time_field.SetValue('%u minutes to empty'%(time_remaining)) 00116 if time_remaining > 10: 00117 self.time_field.SetBackgroundColour("Light Green") 00118 elif time_remaining > 5: 00119 self.time_field.SetBackgroundColour("Orange") 00120 else: 00121 self.time_field.SetBackgroundColour("Red") 00122 00123 self._messages = [] 00124 00125 self._mutex.release() 00126 00127 self.Refresh() 00128 00129 def start_timer(self): 00130 # Set a timer to expire one second after we expect to timeout. This 00131 # way a timer event happens at most once every second if the 00132 # simulation is in slow motion, and we are at most one second late if 00133 # the simulation is happening in real time. 00134 interval = rospy.get_time() - self.last_message_time; 00135 sleep_time = 1000 * (self.timeout_interval - interval + 1); 00136 self.timer.Start(sleep_time, True) 00137 #print 'start_timer %f\n'%sleep_time 00138 00139 def on_timer(self, event): 00140 self._mutex.acquire() 00141 00142 interval = rospy.get_time() - self.last_message_time 00143 00144 #print 'on_timer %f %f %f\n'%(rospy.get_time(), self.last_message_time, interval) 00145 00146 # Consider that we have timed out after 5 seconds of ros time, or if 00147 # the ros time jumps back (in that case something fishy just happened 00148 # and the previously displayed value is most likely stale). 00149 if interval > self.timeout_interval or interval < 0: 00150 #print 'timeout\n' 00151 self.power_text.Disable() 00152 self.time_field.Disable() 00153 self.status_text.Disable() 00154 self.time_field.SetBackgroundColour("White") 00155 self.capacity_text.Disable() 00156 else: 00157 self.start_timer() 00158 00159 self._mutex.release() 00160 self.Refresh()