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


laptop_battery_monitor
Author(s): Daniel Stonier
autogenerated on Fri Feb 12 2016 01:51:16