Go to the documentation of this file.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
00034
00035
00036
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
00057
00058
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
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
00103 if last.AC_present == 0 and last.relative_capacity < DISCHARGE_LEVEL:
00104 out.battery_status = ChargeStatus.HUNGRY
00105
00106
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