cpu_monitor.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 #
3 # Software License Agreement (BSD License)
4 #
5 # Copyright (c) 2017, TNO IVS, Helmond, Netherlands
6 # All rights reserved.
7 #
8 # Redistribution and use in source and binary forms, with or without
9 # modification, are permitted provided that the following conditions
10 # are met:
11 #
12 # * Redistributions of source code must retain the above copyright
13 # notice, this list of conditions and the following disclaimer.
14 # * Redistributions in binary form must reproduce the above
15 # copyright notice, this list of conditions and the following
16 # disclaimer in the documentation and/or other materials provided
17 # with the distribution.
18 # * Neither the name of the TNO IVS nor the names of its
19 # contributors may be used to endorse or promote products derived
20 # from this software without specific prior written permission.
21 #
22 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 # POSSIBILITY OF SUCH DAMAGE.
34 
35 # \author Rein Appeldoorn
36 
37 import collections
38 import socket
39 
40 import psutil
41 import rospy
42 from diagnostic_msgs.msg import DiagnosticStatus
43 from diagnostic_updater import DiagnosticTask, Updater
44 
45 
47  def __init__(self, warning_percentage, window=1):
48  DiagnosticTask.__init__(self, "CPU Information")
49  self._warning_percentage = int(warning_percentage)
50  self._readings = collections.deque(maxlen=window)
51 
53  def avg(lst):
54  return float(sum(lst)) / len(lst) if lst else float('nan')
55 
56  return [avg(cpu_percentages) for cpu_percentages in zip(*self._readings)]
57 
58  def run(self, stat):
59  self._readings.append(psutil.cpu_percent(percpu=True))
60  cpu_percentages = self._get_average_reading()
61  cpu_average = sum(cpu_percentages) / len(cpu_percentages)
62 
63  stat.add("CPU Load Average", "{:.2f}".format(cpu_average))
64 
65  warn = False
66  for idx, val in enumerate(cpu_percentages):
67  stat.add("CPU {} Load".format(idx), "{:.2f}".format(val))
68  if val > self._warning_percentage:
69  warn = True
70 
71  if warn:
72  stat.summary(DiagnosticStatus.WARN,
73  "At least one CPU exceeds {:d} percent".format(self._warning_percentage))
74  else:
75  stat.summary(DiagnosticStatus.OK, "CPU Average {:.2f} percent".format(cpu_average))
76 
77  return stat
78 
79 
80 def main():
81  hostname = socket.gethostname()
82  rospy.init_node('cpu_monitor_%s' % hostname.replace("-", "_"))
83 
84  updater = Updater()
85  updater.setHardwareID(hostname)
86  updater.add(CpuTask(rospy.get_param("~warning_percentage", 90), rospy.get_param("~window", 1)))
87 
88  rate = rospy.Rate(rospy.get_param("~rate", 1))
89  while not rospy.is_shutdown():
90  rate.sleep()
91  updater.update()
92 
93 
94 if __name__ == '__main__':
95  main()
def __init__(self, warning_percentage, window=1)
Definition: cpu_monitor.py:47


diagnostic_common_diagnostics
Author(s): Brice Rebsamen
autogenerated on Mon Feb 28 2022 22:18:19