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


linux_hardware
Author(s): Daniel Stonier
autogenerated on Mon Oct 6 2014 08:01:08