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 import roslib
00037 roslib.load_manifest('maxwell_defs')
00038 import rospy
00039 import diagnostic_msgs.msg
00040 import subprocess
00041
00042 def laptop_battery_monitor():
00043 diag_pub = rospy.Publisher('/diagnostics', diagnostic_msgs.msg.DiagnosticArray)
00044 rospy.init_node('laptop_battery_monitor')
00045 while not rospy.is_shutdown():
00046
00047
00048 diag = diagnostic_msgs.msg.DiagnosticArray()
00049 diag.header.stamp = rospy.Time.now()
00050
00051
00052 stat = diagnostic_msgs.msg.DiagnosticStatus()
00053 stat.name = "Laptop Battery"
00054 stat.level = diagnostic_msgs.msg.DiagnosticStatus.OK
00055 stat.message = "OK"
00056
00057
00058 cmd = ['upower', '-d']
00059 command_line = subprocess.Popen(cmd, stdout=subprocess.PIPE, stderr=subprocess.STDOUT)
00060 (pstd_out, pstd_err) = command_line.communicate()
00061 raw_battery_stats = {}
00062 for l in pstd_out.split('\n'):
00063 l_vec = l.split(':')
00064 l_stripped = [l.strip() for l in l_vec]
00065 if len(l_stripped) == 2:
00066 k, v = l_stripped
00067 if k == 'voltage':
00068 raw_battery_stats['voltage'] = v.split()[0]
00069 elif k == 'energy-rate':
00070 raw_battery_stats['watts'] = v.split()[0]
00071 elif k == 'energy-full':
00072 raw_battery_stats['energy_full_wh'] = v.split()[0]
00073 elif k == 'percentage':
00074 raw_battery_stats['percentage'] = v.rstrip('%')
00075 elif k == 'on-battery':
00076 raw_battery_stats['on_battery'] = v
00077
00078 voltage = float(raw_battery_stats['voltage'])
00079 watts = float(raw_battery_stats['watts'])
00080 if raw_battery_stats['on_battery'] == 'no':
00081 current_direction = 1
00082 else:
00083 current_direction = -1
00084 current = current_direction * watts / voltage
00085 capacity_fraction = float(raw_battery_stats['percentage'])/100.0
00086 energy_full = float(raw_battery_stats['energy_full_wh'])
00087 capacity = energy_full / voltage
00088 charge = capacity_fraction * capacity
00089
00090 stat.values.append(diagnostic_msgs.msg.KeyValue("Voltage (V)", str(voltage)))
00091 stat.values.append(diagnostic_msgs.msg.KeyValue("Current (A)", str(current)))
00092 stat.values.append(diagnostic_msgs.msg.KeyValue("Charge (Ah)", str(charge)))
00093 stat.values.append(diagnostic_msgs.msg.KeyValue("Capacity (Ah)", str(capacity)))
00094
00095
00096 diag.status.append(stat)
00097
00098
00099 diag_pub.publish(diag)
00100 rospy.sleep(1.0)
00101
00102
00103 if __name__ == '__main__':
00104 try:
00105 laptop_battery_monitor()
00106 except rospy.ROSInterruptException: pass
00107 except IOError: pass
00108 except KeyError: pass