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
00037 import rospy
00038 from diagnostic_updater import DiagnosticTask, Updater
00039 from diagnostic_msgs.msg import DiagnosticStatus
00040
00041 import psutil
00042 import socket
00043
00044
00045 class CpuTask(DiagnosticTask):
00046 def __init__(self, warning_percentage):
00047 DiagnosticTask.__init__(self, "CPU Information")
00048 self._warning_percentage = int(warning_percentage)
00049
00050 def run(self, stat):
00051 cpu_percentages = psutil.cpu_percent(percpu=True)
00052 cpu_average = sum(cpu_percentages) / len(cpu_percentages)
00053
00054 stat.add("CPU Load Average", cpu_average)
00055
00056 warn = False
00057 for idx, val in enumerate(cpu_percentages):
00058 stat.add("CPU {} Load".format(idx), "{}".format(val))
00059 if val > self._warning_percentage:
00060 warn = True
00061
00062 if warn:
00063 stat.summary(DiagnosticStatus.WARN, "At least one CPU exceeds %d percent" % self._warning_percentage)
00064 else:
00065 stat.summary(DiagnosticStatus.OK, "CPU Average %.1f percent" % cpu_average)
00066
00067 return stat
00068
00069
00070 def main():
00071 hostname = socket.gethostname()
00072 rospy.init_node('cpu_monitor_%s' % hostname.replace("-", "_"))
00073
00074 updater = Updater()
00075 updater.setHardwareID(hostname)
00076 updater.add(CpuTask(rospy.get_param("~warning_percentage", 90)))
00077
00078 rate = rospy.Rate(rospy.get_param("~rate", 1))
00079 while not rospy.is_shutdown():
00080 rate.sleep()
00081 updater.update()
00082
00083
00084 if __name__ == '__main__':
00085 main()