$search
00001 #!/usr/bin/python 00002 # Software License Agreement (BSD License) 00003 # 00004 # Copyright (c) 2010, Willow Garage, Inc. 00005 # All rights reserved. 00006 # 00007 # Redistribution and use in source and binary forms, with or without 00008 # modification, are permitted provided that the following conditions 00009 # are met: 00010 # 00011 # * Redistributions of source code must retain the above copyright 00012 # notice, this list of conditions and the following disclaimer. 00013 # * Redistributions in binary form must reproduce the above 00014 # copyright notice, this list of conditions and the following 00015 # disclaimer in the documentation and/or other materials provided 00016 # with the distribution. 00017 # * Neither the name of the Willow Garage nor the names of its 00018 # contributors may be used to endorse or promote products derived 00019 # from this software without specific prior written permission. 00020 # 00021 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 # POSSIBILITY OF SUCH DAMAGE. 00033 # 00034 00035 ##\author Kevin Watts 00036 ##\brief Monitors battery status, and send high/low power status messages 00037 00038 from __future__ import with_statement 00039 00040 PKG = 'continuous_ops_executive' 00041 import roslib; roslib.load_manifest(PKG) 00042 import rospy 00043 00044 import threading 00045 00046 from pr2_msgs.msg import PowerState 00047 from continuous_ops_msgs.msg import ChargeStatus 00048 00049 from collections import deque 00050 00051 CHARGE_LEVEL = 95 00052 DISCHARGE_LEVEL = 40 00053 00054 BUFFER_SIZE = 10 00055 00056 # Return true if we are fully charged 00057 # True if we have 5 consecutive messages above charge level 00058 # And last message shows we're still charging 00059 def _check_stuffed(msgs): 00060 if not len(msgs) >= 5: 00061 return False 00062 00063 for i in range(0, 5): 00064 m = msgs[-1 * i] 00065 if not m.relative_capacity > CHARGE_LEVEL: 00066 return False 00067 00068 if msgs[-1].AC_present == 0: 00069 return False 00070 00071 return True 00072 00073 class BatteryMonitor(object): 00074 def __init__(self): 00075 self._mutex = threading.Lock() 00076 self._state_pub = rospy.Publisher('charge_status', ChargeStatus, latch=True) 00077 self._msgs = deque() 00078 self._power_sub = rospy.Subscriber('power_state', PowerState, self._power_cb) 00079 00080 def _power_cb(self, msg): 00081 with self._mutex: 00082 self._msgs.append(msg) 00083 00084 # Clip deque to max length 00085 while len(self._msgs) > BUFFER_SIZE: 00086 self._msgs.popleft() 00087 00088 def update(self): 00089 with self._mutex: 00090 if not self._msgs: 00091 return 00092 00093 out = ChargeStatus() 00094 out.charge_status = ChargeStatus.UNPLUGGED 00095 out.battery_status = ChargeStatus.HAPPY 00096 00097 last = self._msgs[-1] 00098 00099 if last.AC_present > 0: 00100 out.charge_status = ChargeStatus.CHARGING 00101 00102 # Hungry if we're not charging and below the minimum level 00103 if last.AC_present == 0 and last.relative_capacity < DISCHARGE_LEVEL: 00104 out.battery_status = ChargeStatus.HUNGRY 00105 00106 # Check if we should be stuffed 00107 if _check_stuffed(self._msgs): 00108 out.battery_status = ChargeStatus.STUFFED 00109 00110 self._state_pub.publish(out) 00111 00112 00113 if __name__ == '__main__': 00114 rospy.init_node('battery_monitor') 00115 bm = BatteryMonitor() 00116 00117 try: 00118 my_rate = rospy.Rate(1.0) 00119 while not rospy.is_shutdown(): 00120 bm.update() 00121 my_rate.sleep() 00122 except KeyboardInterrupt, e: 00123 pass 00124 except Exception, e: 00125 import traceback 00126 traceback.print_exc() 00127 00128