ram_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, "RAM Information")
49  self._warning_percentage = int(warning_percentage)
50  self._readings = collections.deque(maxlen=window)
51 
52  def run(self, stat):
53  self._readings.append(psutil.virtual_memory().percent)
54  ram_average = sum(self._readings) / len(self._readings)
55 
56  stat.add("RAM Load Average", "{:.2f}".format(ram_average))
57 
58  if ram_average > self._warning_percentage:
59  stat.summary(DiagnosticStatus.WARN,
60  "RAM Average exceeds {:d} percent".format(self._warning_percentage))
61  else:
62  stat.summary(DiagnosticStatus.OK, "RAM Average {:.2f} percent".format(ram_average))
63 
64  return stat
65 
66 
67 def main():
68  hostname = socket.gethostname()
69  rospy.init_node('ram_monitor_%s' % hostname.replace("-", "_"))
70 
71  updater = Updater()
72  updater.setHardwareID(hostname)
73  updater.add(RamTask(rospy.get_param("~warning_percentage", 90), rospy.get_param("~window", 1)))
74 
75  rate = rospy.Rate(rospy.get_param("~rate", 1))
76  while not rospy.is_shutdown():
77  rate.sleep()
78  updater.update()
79 
80 
81 if __name__ == '__main__':
82  try:
83  main()
84  except (rospy.ROSInterruptException, KeyboardInterrupt) as e:
85  pass
diagnostic_common_diagnostics.ram_monitor.RamTask._warning_percentage
_warning_percentage
Definition: ram_monitor.py:49
diagnostic_common_diagnostics.ram_monitor.RamTask.__init__
def __init__(self, warning_percentage, window=1)
Definition: ram_monitor.py:47
diagnostic_updater::Updater
diagnostic_common_diagnostics.ram_monitor.RamTask
Definition: ram_monitor.py:46
diagnostic_updater::DiagnosticTask
diagnostic_common_diagnostics.ram_monitor.RamTask.run
def run(self, stat)
Definition: ram_monitor.py:52
diagnostic_common_diagnostics.ram_monitor.main
def main()
Definition: ram_monitor.py:67
diagnostic_common_diagnostics.ram_monitor.RamTask._readings
_readings
Definition: ram_monitor.py:50


diagnostic_common_diagnostics
Author(s): Brice Rebsamen
autogenerated on Tue Nov 15 2022 03:17:21