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 rospy
38 from diagnostic_updater import DiagnosticTask, Updater
39 from diagnostic_msgs.msg import DiagnosticStatus
40 
41 import psutil
42 import socket
43 
44 
46  def __init__(self, warning_percentage):
47  DiagnosticTask.__init__(self, "CPU Information")
48  self._warning_percentage = int(warning_percentage)
49 
50  def run(self, stat):
51  cpu_percentages = psutil.cpu_percent(percpu=True)
52  cpu_average = sum(cpu_percentages) / len(cpu_percentages)
53 
54  stat.add("CPU Load Average", cpu_average)
55 
56  warn = False
57  for idx, val in enumerate(cpu_percentages):
58  stat.add("CPU {} Load".format(idx), "{}".format(val))
59  if val > self._warning_percentage:
60  warn = True
61 
62  if warn:
63  stat.summary(DiagnosticStatus.WARN, "At least one CPU exceeds %d percent" % self._warning_percentage)
64  else:
65  stat.summary(DiagnosticStatus.OK, "CPU Average %.1f percent" % cpu_average)
66 
67  return stat
68 
69 
70 def main():
71  hostname = socket.gethostname()
72  rospy.init_node('cpu_monitor_%s' % hostname.replace("-", "_"))
73 
74  updater = Updater()
75  updater.setHardwareID(hostname)
76  updater.add(CpuTask(rospy.get_param("~warning_percentage", 90)))
77 
78  rate = rospy.Rate(rospy.get_param("~rate", 1))
79  while not rospy.is_shutdown():
80  rate.sleep()
81  updater.update()
82 
83 
84 if __name__ == '__main__':
85  main()
def __init__(self, warning_percentage)
Definition: cpu_monitor.py:46


diagnostic_common_diagnostics
Author(s): Brice Rebsamen
autogenerated on Wed Mar 27 2019 03:02:24