Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015 import multiprocessing
00016 import numpy as np
00017 import psutil
00018
00019 import rosgraph
00020 import rospy
00021
00022 from ros_statistics_msgs.msg import HostStatistics
00023
00024
00025 class HostMonitor(object):
00026 """ Tracks cpu and memory information of the host. """
00027 def __init__(self):
00028 self._hostname = rosgraph.network.get_host_name()
00029 self._ipaddress = rosgraph.network.get_local_address()
00030 self._cpus_available = multiprocessing.cpu_count()
00031
00032 self.cpu_load_log = list()
00033 self.phymem_used_log = list()
00034 self.phymem_avail_log = list()
00035 self.start_time = rospy.get_rostime()
00036
00037 def update(self):
00038 """ Record information about the cpu and memory usage for this host into a buffer """
00039 self.cpu_load_log.append(psutil.cpu_percent(interval=0, percpu=True))
00040 self.phymem_used_log.append(psutil.used_phymem())
00041 self.phymem_avail_log.append(psutil.avail_phymem())
00042
00043 def get_statistics(self):
00044 """ Returns HostStatistics() using buffered information.
00045 :returns: statistics information collected about the host
00046 :rtype: HostStatistics
00047 """
00048
00049 statistics = HostStatistics()
00050 statistics.hostname = self._hostname
00051 statistics.ipaddress = self._ipaddress
00052 statistics.window_start = self.start_time
00053 statistics.window_stop = rospy.get_rostime()
00054 statistics.samples = len(self.cpu_load_log)
00055
00056 if len(self.cpu_load_log) > 0:
00057 cpu_load_log = np.array(self.cpu_load_log)
00058 cpu_load_log = cpu_load_log.transpose()
00059 for cpu in range(self._cpus_available):
00060 statistics.cpu_load_mean.append(np.mean(cpu_load_log[cpu]))
00061 statistics.cpu_load_std.append(np.std(cpu_load_log[cpu]))
00062 statistics.cpu_load_max.append(np.max(cpu_load_log[cpu]))
00063 if len(self.phymem_used_log) > 0:
00064 phymem_used_log = np.array(self.phymem_used_log)
00065 statistics.phymem_used_mean = np.mean(phymem_used_log)
00066 statistics.phymem_used_std = np.std(phymem_used_log)
00067 statistics.phymem_used_max = np.max(phymem_used_log)
00068 if len(self.phymem_avail_log) > 0:
00069 phymem_avail_log = np.array(self.phymem_avail_log)
00070 statistics.phymem_avail_mean = np.mean(phymem_avail_log)
00071 statistics.phymem_avail_std = np.std(phymem_avail_log)
00072 statistics.phymem_avail_max = np.max(phymem_avail_log)
00073 return statistics
00074
00075 def reset(self):
00076 """ Clears the information buffer. """
00077 self.cpu_load_log = list()
00078 self.phymem_used_log = list()
00079 self.phymem_avail_log = list()
00080 self.start_time = rospy.get_rostime()