42 from diagnostic_msgs.msg
import DiagnosticStatus
43 from diagnostic_updater
import DiagnosticTask, Updater
47 def __init__(self, warning_percentage, window=1):
48 DiagnosticTask.__init__(self,
"CPU Information")
54 return float(sum(lst)) / len(lst)
if lst
else float(
'nan')
56 return [avg(cpu_percentages)
for cpu_percentages
in zip(*self.
_readings)]
59 self._readings.append(psutil.cpu_percent(percpu=
True))
61 cpu_average = sum(cpu_percentages) / len(cpu_percentages)
63 stat.add(
"CPU Load Average",
"{:.2f}".format(cpu_average))
66 for idx, val
in enumerate(cpu_percentages):
67 stat.add(
"CPU {} Load".format(idx),
"{:.2f}".format(val))
72 stat.summary(DiagnosticStatus.WARN,
75 stat.summary(DiagnosticStatus.OK,
"CPU Average {:.2f} percent".format(cpu_average))
81 hostname = socket.gethostname()
82 rospy.init_node(
'cpu_monitor_%s' % hostname.replace(
"-",
"_"))
85 updater.setHardwareID(hostname)
86 updater.add(
CpuTask(rospy.get_param(
"~warning_percentage", 90), rospy.get_param(
"~window", 1)))
88 rate = rospy.Rate(rospy.get_param(
"~rate", 1))
89 while not rospy.is_shutdown():
94 if __name__ ==
'__main__':
def __init__(self, warning_percentage, window=1)
def _get_average_reading(self)