Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015 import numpy as np
00016 import psutil
00017
00018 import rosgraph
00019 import rospy
00020
00021 from ros_statistics_msgs.msg import NodeStatistics
00022
00023
00024 class NodeMonitor(object):
00025 """ Tracks process statistics of a PID. """
00026 def __init__(self, name, uri, pid):
00027 """
00028 :param str name: the registered node name
00029 :param str uri: the xmlrpc uri of the node
00030 :param int pid: the process PID of this node
00031 """
00032 self.node = name
00033 self.hostname = rosgraph.network.get_host_name()
00034 self.uri = uri
00035 self.pid = pid
00036 self._process = psutil.Process(int(self.pid))
00037 self._process_ok = True
00038
00039 self.cpu_log = list()
00040 self.virt_log = list()
00041 self.res_log = list()
00042 self.num_threads = 0
00043 self.start_time = rospy.get_rostime()
00044
00045 def is_running(self):
00046 """ Returns if we are still monitoring the process of the PID.
00047 :rtype: bool
00048 """
00049 if self._process is None:
00050 return False
00051 return self._process.is_running()
00052
00053 def update(self):
00054 """ Record cpu and memory information about this procress into a buffer """
00055 try:
00056 self.cpu_log.append(self._process.get_cpu_percent(interval=0))
00057 virt, real = self._process.get_memory_info()
00058 self.virt_log.append(virt)
00059 self.res_log.append(real)
00060 self.num_threads = max(self.num_threads, self._process.get_num_threads())
00061 except psutil.NoSuchProcess:
00062 rospy.logwarn("Lost Node Monitor for '%s'" % self.node)
00063 self._process = None
00064 self._process_ok = False
00065
00066 def get_statistics(self):
00067 """ Returns NodeStatistics() using information stored in the buffer.
00068 :returns: statistics information collected about the process
00069 :rtype: NodeStatistics
00070 """
00071 statistics = NodeStatistics()
00072 statistics.node = self.node
00073 statistics.host = self.hostname
00074 statistics.uri = self.uri
00075 statistics.pid = str(self.pid)
00076 statistics.samples = len(self.cpu_log)
00077 statistics.threads = self.num_threads
00078 statistics.window_start = self.start_time
00079 statistics.window_stop = rospy.get_rostime()
00080
00081 if len(self.cpu_log) > 0:
00082 cpu_log = np.array(self.cpu_log)
00083 statistics.cpu_load_mean = np.mean(cpu_log)
00084 statistics.cpu_load_std = np.std(cpu_log)
00085 statistics.cpu_load_max = np.max(cpu_log)
00086 if len(self.virt_log) > 0:
00087 virt_log = np.array(self.virt_log)
00088 statistics.virt_mem_mean = np.mean(virt_log)
00089 statistics.virt_mem_std = np.std(virt_log)
00090 statistics.virt_mem_max = np.max(virt_log)
00091 if len(self.res_log) > 0:
00092 res_log = np.array(self.res_log)
00093 statistics.real_mem_mean = np.mean(res_log)
00094 statistics.real_mem_std = np.std(res_log)
00095 statistics.real_mem_max = np.max(res_log)
00096 return statistics
00097
00098 def reset(self):
00099 """ Clears the statistics information stored in the buffer """
00100 self.cpu_log = list()
00101 self.virt_log = list()
00102 self.res_log = list()
00103 self.num_threads = 0
00104 self.start_time = rospy.get_rostime()