cpu_monitor.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 # Software License Agreement (BSD License)
00004 #
00005 # Copyright (c) 2011, Robot Control and Pattern Recognition Group, Warsaw University of Technology
00006 #
00007 # All rights reserved.
00008 # 
00009 # Redistribution and use in source and binary forms, with or without
00010 # modification, are permitted provided that the following conditions are met:
00011 #     * Redistributions of source code must retain the above copyright
00012 #       notice, this list of conditions and the following disclaimer.
00013 #     * Redistributions in binary form must reproduce the above copyright
00014 #       notice, this list of conditions and the following disclaimer in the
00015 #       documentation and/or other materials provided with the distribution.
00016 #     * Neither the name of the <organization> nor the
00017 #       names of its contributors may be used to endorse or promote products
00018 #       derived from this software without specific prior written permission.
00019 # 
00020 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00021 # ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00022 # WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00023 # DISCLAIMED. IN NO EVENT SHALL <COPYRIGHT HOLDER> BE LIABLE FOR ANY
00024 # DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00025 # (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00026 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00027 # ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00028 # (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00029 # SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00030 
00031 
00032 import roslib
00033 roslib.load_manifest('elektron_monitor')
00034 
00035 import rospy
00036 import diagnostic_msgs.msg
00037 
00038 import subprocess
00039 import re
00040 
00041 def cpu_monitor():
00042     """ 
00043     Function for retrieving information about current CPU usage etc.
00044     """
00045     
00046     diag_pub = rospy.Publisher('/diagnostics', diagnostic_msgs.msg.DiagnosticArray)
00047     rospy.init_node('cpu_monitor')
00048     
00049     prev_total = [0, 0, 0, 0, 0, 0, 0, 0]
00050     prev_idle = [0, 0, 0, 0, 0, 0, 0, 0]
00051     
00052     while not rospy.is_shutdown():
00053         
00054         #Main header
00055         diag = diagnostic_msgs.msg.DiagnosticArray()
00056         diag.header.stamp = rospy.Time.now()
00057 
00058         lines = open("/proc/stat", "r").readlines()
00059        
00060         p1 = subprocess.Popen(["cat", "/proc/cpuinfo"], stdout=subprocess.PIPE)
00061         p2 = subprocess.Popen(["grep", "MHz"], stdin=p1.stdout, stdout=subprocess.PIPE)
00062         
00063         
00064         p1.stdout.close()  # Allow p1 to receive a SIGPIPE if p2 exits.
00065         freqs = p2.communicate()[0].split("\n")
00066 
00067 
00068         id = 0
00069 
00070         for line in lines[1:]:
00071             jifs = line.split()
00072             
00073             if (jifs[0] == "intr"):
00074                 break
00075             
00076             cpuname = jifs[0]
00077             total = 0
00078             idle = int(jifs[4])
00079             
00080             for jif in jifs[1:]:
00081                 total = total + int(jif) 
00082             
00083             if (prev_total[id] < 0):
00084                 prev_total[id] = total
00085                 prev_idle[id] = idle
00086                 
00087             diff_total = total - prev_total[id]
00088             diff_idle = idle - prev_idle[id]
00089             
00090             prev_total[id] = total
00091             prev_idle[id] = idle
00092                 
00093             usage = 100.0 * (diff_total - diff_idle) / diff_total
00094             
00095             cur_freq = float(freqs[id].split(":")[1])
00096             max_freq = float(open("/sys/devices/system/cpu/"+cpuname+"/cpufreq/cpuinfo_max_freq", "r").readlines()[0]) / 1000
00097             
00098             # CPU info                                                                                                                              
00099             stat = diagnostic_msgs.msg.DiagnosticStatus()
00100             stat.name = cpuname
00101             stat.level = diagnostic_msgs.msg.DiagnosticStatus.OK
00102             stat.message = "OK"
00103         
00104             stat.values.append(diagnostic_msgs.msg.KeyValue("usage", str(usage)))
00105             stat.values.append(diagnostic_msgs.msg.KeyValue("cur_freq", str(cur_freq)))
00106             stat.values.append(diagnostic_msgs.msg.KeyValue("max_freq", str(max_freq)))
00107     
00108             #append
00109             diag.status.append(stat)
00110             
00111             # increase processor number
00112             id = id + 1
00113         
00114         #
00115         # Memory info
00116         #
00117         
00118         p1 = subprocess.Popen(["free","-m"], stdout=subprocess.PIPE)
00119         lines = p1.communicate()[0]
00120         
00121         lines = lines.split("\n")
00122         data = lines[1].split()
00123         mem_total = data[1]
00124         mem_used = data[2]
00125         mem_free = data[3]
00126         mem_shared = data[4]
00127         mem_buffers = data[5]
00128         mem_chached = data[6]
00129         # Memory info                                                                                                                              
00130         stat = diagnostic_msgs.msg.DiagnosticStatus()
00131         stat.name = "Memory"
00132         stat.level = diagnostic_msgs.msg.DiagnosticStatus.OK
00133         stat.message = "OK"
00134         
00135         stat.values.append(diagnostic_msgs.msg.KeyValue("total", mem_total))
00136         stat.values.append(diagnostic_msgs.msg.KeyValue("used", mem_used))
00137         stat.values.append(diagnostic_msgs.msg.KeyValue("free", mem_free))
00138         stat.values.append(diagnostic_msgs.msg.KeyValue("shared", mem_shared))
00139         stat.values.append(diagnostic_msgs.msg.KeyValue("buffers", mem_buffers))
00140         stat.values.append(diagnostic_msgs.msg.KeyValue("cached", mem_chached))
00141         
00142         
00143         diag.status.append(stat)
00144         
00145         #publish
00146         diag_pub.publish(diag)
00147             
00148             
00149         rospy.sleep(2.0)
00150 
00151 
00152 if __name__ == '__main__':
00153     try:
00154         cpu_monitor()
00155     except rospy.ROSInterruptException: pass
00156     except IOError: pass
00157     except KeyError: pass
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


elektron_monitor
Author(s): Maciej Stefanczyk
autogenerated on Thu Nov 14 2013 11:56:01