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