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 division
00039
00040 from collections import deque
00041 import threading
00042 import copy
00043 import yaml
00044 import math
00045 import rospy
00046 import os
00047
00048 from linux_hardware.msg import LaptopChargeStatus
00049 from diagnostic_msgs.msg import DiagnosticStatus, DiagnosticArray, KeyValue
00050
00051 def _strip_Ah(raw_val):
00052 if 'mAh' in raw_val:
00053 rv = float(raw_val.rstrip('mAh').strip()) / 1000.0
00054 elif 'Ah' in raw_val:
00055 rv = float(raw_val.rstrip('Ah').strip())
00056 elif 'mWh' in raw_val:
00057 rv = float(raw_val.rstrip('mWh').strip()) / 1000.0
00058 elif 'Wh' in raw_val:
00059 rv = float(raw_val.rstrip('Wh').strip())
00060 else:
00061 raise Exception('Value %s did not have supported units. (mAh,Ah,mWh,Wh)' % raw_val)
00062 return rv
00063
00064 def _strip_V(raw_val):
00065 if 'mV' in raw_val:
00066 rv = float(raw_val.rstrip('mV').strip()) / 1000.0
00067 elif 'V' in raw_val:
00068 rv = float(raw_val.rstrip('V').strip())
00069 else:
00070 raise Exception('Value %s did not have "V" or "mV"' % raw_val)
00071 return rv
00072
00073 def _strip_A(raw_val):
00074 if 'mA' in raw_val:
00075 rv = float(raw_val.rstrip('mA').strip()) / 1000.0
00076 elif 'A' in raw_val:
00077 rv = float(raw_val.rstrip('A').strip())
00078 elif 'mW' in raw_val:
00079 rv = float(raw_val.rstrip('mW').strip()) / 1000.0
00080 elif 'W' in raw_val:
00081 rv = float(raw_val.rstrip('W').strip())
00082 else:
00083 raise Exception('Value %s did not have supported units. (mAh,Ah,mWh,Wh)' % raw_val)
00084 return rv
00085
00086 def slerp(filename):
00087 f = open(filename, 'r')
00088 data = f.read()
00089 f.close()
00090 data = data.replace('\t', ' ')
00091 return data
00092
00093 def _read_string(filename, default=""):
00094 if not os.access(filename, os.F_OK):
00095 return default
00096 f = open(filename, 'r')
00097 data = f.read()
00098 f.close()
00099 return data
00100
00101 def _read_number(filename, default=0):
00102 try:
00103 data = int(_read_string(filename))
00104 return data
00105 except exceptions.ValueError:
00106 return default
00107
00108 def _check_battery_info(_battery_acpi_path):
00109 if _battery_acpi_path.startswith('/proc'):
00110
00111 if os.access(_battery_acpi_path, os.F_OK):
00112 o = slerp(_battery_acpi_path+'/info')
00113 else:
00114 raise Exception(_battery_acpi_path+' does not exist')
00115
00116 batt_info = yaml.load(o)
00117 design_capacity = _strip_Ah(batt_info.get('design capacity', '0 mAh'))
00118 last_full_capacity = _strip_Ah(batt_info.get('last full capacity', '0 mAh'))
00119 else:
00120
00121 if os.path.exists(_battery_acpi_path + '/energy_full'):
00122 design_capacity = _read_number(_battery_acpi_path + '/energy_full_design')/10e5
00123 else:
00124 design_capacity = _read_number(_battery_acpi_path + '/charge_full_design')/10e5
00125
00126 if os.path.exists(_battery_acpi_path + '/energy_full_design'):
00127 last_full_capacity = _read_number(_battery_acpi_path + '/energy_full')/10e5
00128 else:
00129 last_full_capacity = _read_number(_battery_acpi_path + '/charge_full')/10e5
00130
00131 return (design_capacity, last_full_capacity)
00132
00133 state_to_val = {'charged': LaptopChargeStatus.CHARGED,
00134 'full': LaptopChargeStatus.CHARGED,
00135 'charging': LaptopChargeStatus.CHARGING,
00136 'discharging': LaptopChargeStatus.DISCHARGING,
00137 'unknown': LaptopChargeStatus.CHARGING, }
00138
00139 diag_level_to_msg = { DiagnosticStatus.OK: 'OK',
00140 DiagnosticStatus.WARN: 'Warning',
00141 DiagnosticStatus.ERROR: 'Error' }
00142
00143 def _check_battery_state(_battery_acpi_path):
00144 """
00145 @return LaptopChargeStatus
00146 """
00147 rv = LaptopChargeStatus()
00148
00149 if _battery_acpi_path.startswith('/proc'):
00150
00151 if os.access(_battery_acpi_path, os.F_OK):
00152 o = slerp(_battery_acpi_path+'/state')
00153 else:
00154 raise Exception(_battery_acpi_path+' does not exist')
00155
00156 batt_info = yaml.load(o)
00157
00158 state = batt_info.get('charging state', 'discharging')
00159 rv.charge_state = state_to_val.get(state, 0)
00160 rv.rate = _strip_A(batt_info.get('present rate', '-1 mA'))
00161 if rv.charge_state == LaptopChargeStatus.DISCHARGING:
00162 rv.rate = math.copysign(rv.rate, -1)
00163
00164 rv.charge = _strip_Ah(batt_info.get('remaining capacity', '-1 mAh'))
00165 rv.voltage = _strip_V(batt_info.get('present voltage', '-1 mV'))
00166 rv.present = batt_info.get('present', False)
00167
00168 rv.header.stamp = rospy.get_rostime()
00169 else:
00170
00171
00172 state = _read_string(_battery_acpi_path+'/status', 'discharging').lower().rstrip()
00173 rv.charge_state = state_to_val.get(state, 0)
00174
00175 if os.path.exists(_battery_acpi_path + '/power_now'):
00176 rv.rate = _read_number(_battery_acpi_path + '/power_now')/10e5
00177 else:
00178 rv.rate = _read_number(_battery_acpi_path + '/current_now')/10e5
00179
00180 if rv.charge_state == LaptopChargeStatus.DISCHARGING:
00181 rv.rate = math.copysign(rv.rate, -1)
00182
00183 if os.path.exists(_battery_acpi_path + '/energy_now'):
00184 rv.charge = _read_number(_battery_acpi_path + '/energy_now')/10e5
00185 else:
00186 rv.charge = _read_number(_battery_acpi_path + '/charge_now')/10e5
00187
00188 rv.voltage = _read_number(_battery_acpi_path + '/voltage_now')/10e5
00189 rv.present = _read_number(_battery_acpi_path + '/present') == 1
00190
00191 rv.header.stamp = rospy.get_rostime()
00192
00193
00194
00195 return rv
00196
00197 def _laptop_charge_to_diag(laptop_msg):
00198 rv = DiagnosticStatus()
00199 rv.level = DiagnosticStatus.OK
00200 rv.message = 'OK'
00201 rv.name = 'Laptop Battery'
00202
00203 if not laptop_msg.present:
00204 rv.level = DiagnosticStatus.ERROR
00205 rv.message = 'Laptop battery missing'
00206
00207 rv.values.append(KeyValue('Voltage (V)', str(laptop_msg.voltage)))
00208 rv.values.append(KeyValue('Current (A)', str(laptop_msg.rate)))
00209 rv.values.append(KeyValue('Charge (Ah)', str(laptop_msg.charge)))
00210 rv.values.append(KeyValue('Capacity (Ah)', str(laptop_msg.capacity)))
00211 rv.values.append(KeyValue('Design Capacity (Ah)', str(laptop_msg.design_capacity)))
00212
00213 return rv
00214
00215 class LaptopBatteryMonitor(object):
00216 def __init__(self):
00217 self._mutex = threading.Lock()
00218
00219 self._last_info_update = 0
00220 self._last_state_update = 0
00221 self._msg = LaptopChargeStatus()
00222
00223 self._power_pub = rospy.Publisher('laptop_charge', LaptopChargeStatus, latch=True)
00224 self._diag_pub = rospy.Publisher('/diagnostics', DiagnosticArray)
00225
00226
00227 self._batt_acpi_path = rospy.get_param('~acpi_path', "/sys/class/power_supply/BAT0")
00228 self._batt_design_capacity = 0
00229 self._batt_last_full_capacity = 0
00230 self._last_info_update = 0
00231
00232 self._batt_info_rate = 1 / 60.0
00233 self._batt_info_thread = threading.Thread(target=self._check_batt_info)
00234 self._batt_info_thread.daemon = True
00235 self._batt_info_thread.start()
00236
00237
00238 self._batt_state_rate = 1 / 5.0
00239 self._batt_state_thread = threading.Thread(target=self._check_batt_state)
00240 self._batt_state_thread.daemon = True
00241 self._batt_state_thread.start()
00242
00243 def _check_batt_info(self):
00244 rate = rospy.Rate(self._batt_info_rate)
00245 while not rospy.is_shutdown():
00246 try:
00247 design_cap, last_full_cap = _check_battery_info(self._batt_acpi_path)
00248 with self._mutex:
00249 self._batt_last_full_capacity = last_full_cap
00250 self._batt_design_capacity = design_cap
00251 self._last_info_update = rospy.get_time()
00252 except Exception, e:
00253 rospy.logwarn('Battery : unable to check laptop battery info [%s]' % e)
00254 rospy.signal_shutdown('Battery : unable to check laptop battery info [%s]' % e)
00255
00256 rate.sleep()
00257
00258 def _check_batt_state(self):
00259 rate = rospy.Rate(self._batt_state_rate)
00260 while not rospy.is_shutdown():
00261 try:
00262 msg = _check_battery_state(self._batt_acpi_path)
00263 with self._mutex:
00264 self._msg = msg
00265 self._last_state_update = rospy.get_time()
00266 except Exception, e:
00267 rospy.logwarn('Battery : unable to check laptop battery state [%s]' % e)
00268 rospy.signal_shutdown('Battery : unable to check laptop battery state [%s]' % e)
00269
00270 rate.sleep()
00271
00272 def update(self):
00273 with self._mutex:
00274 diag = DiagnosticArray()
00275 diag.header.stamp = rospy.get_rostime()
00276
00277 info_update_ok = rospy.get_time() - self._last_info_update < 5.0 / self._batt_info_rate
00278 state_update_ok = rospy.get_time() - self._last_state_update < 5.0 / self._batt_state_rate
00279
00280 if info_update_ok:
00281 self._msg.design_capacity = self._batt_design_capacity
00282 self._msg.capacity = self._batt_last_full_capacity
00283 else:
00284 self._msg.design_capacity = 0.0
00285 self._msg.capacity = 0.0
00286
00287 if info_update_ok and state_update_ok and self._msg.capacity != 0:
00288 self._msg.percentage = int(self._msg.charge / self._msg.capacity * 100.0)
00289
00290 diag_stat = _laptop_charge_to_diag(self._msg)
00291 if not info_update_ok or not state_update_ok:
00292 diag_stat.level = DiagnosticStatus.ERROR
00293 diag_stat.message = 'Laptop battery data stale'
00294
00295 diag.status.append(diag_stat)
00296
00297 self._diag_pub.publish(diag)
00298 self._power_pub.publish(self._msg)
00299
00300 if __name__ == '__main__':
00301 rospy.init_node('laptop_battery')
00302
00303 bm = LaptopBatteryMonitor()
00304 try:
00305 r = rospy.Rate(1.0)
00306 while not rospy.is_shutdown():
00307 bm.update()
00308 r.sleep()
00309 except KeyboardInterrupt:
00310 pass
00311 except Exception:
00312 import traceback
00313 traceback.print_exc()
00314