Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015 """
00016 This module implements a ROS node which profiles the resource usage of each node
00017 process being run on the machine, as well as the resources of the host itself.
00018 This information is published on the topics /node_statistics and /host_statistics.
00019
00020 """
00021
00022 import hashlib
00023 import os
00024 import re
00025 import threading
00026 import xmlrpclib
00027
00028 import rospy
00029 import rosgraph
00030 import rosnode
00031 from rosgraph.names import is_legal_name
00032
00033 from ros_statistics_msgs.msg import NodeStatistics
00034 from ros_statistics_msgs.msg import HostStatistics
00035
00036 from host_monitor import HostMonitor
00037 from node_monitor import NodeMonitor
00038
00039
00040 def get_ros_hostname():
00041 """ Try to get ROS_HOSTNAME environment variable.
00042 returns: a ROS compatible hostname, or None.
00043 """
00044 ros_hostname = os.environ.get('ROS_HOSTNAME')
00045 return ros_hostname if is_legal_name(ros_hostname) else None
00046
00047
00048 def get_ros_ip():
00049 """ Try to get the ROS_IP environment variable as a valid name.
00050 Returns: an ip address with '.' replaced with '_', or None if not set.
00051 """
00052 ros_ip = os.environ.get('ROS_IP')
00053 if isinstance(ros_ip, str):
00054 ros_ip = re.sub('\.', '_', ros_ip)
00055 return ros_ip
00056
00057
00058 def get_sys_hostname():
00059 """ If the system hostname is also a valid ROS name, return the hostname.
00060 Otherwise, return the first 6 digits of the md5sum of the hostname
00061 """
00062 hostname = rosgraph.network.get_host_name()
00063 return hostname if is_legal_name(hostname) else hashlib.md5(hostname).hexdigest()[:6]
00064
00065
00066 class Profiler(object):
00067 """ """
00068 def __init__(self, sample_rate=None, update_rate=None):
00069 self.sample_rate = sample_rate or rospy.Duration(0.1)
00070 self.update_rate = update_rate or rospy.Duration(2)
00071
00072
00073
00074
00075 nodename = get_ros_hostname() or get_ros_ip() or get_sys_hostname()
00076
00077 rospy.init_node('rosprofiler_%s' % nodename)
00078 self._master = rosgraph.Master(rospy.names.get_name()[1:])
00079
00080 self._lock = threading.Lock()
00081 self._monitor_timer = None
00082 self._publisher_timer = None
00083 self._graphupdate_timer = None
00084
00085
00086 self._host_monitor = HostMonitor()
00087
00088 self._node_publisher = rospy.Publisher('node_statistics', NodeStatistics, queue_size=10)
00089 self._host_publisher = rospy.Publisher('host_statistics', HostStatistics, queue_size=10)
00090
00091
00092 self._nodes = dict()
00093
00094 def start(self):
00095 """ Starts the Profiler
00096 :raises: ROSInitException when /enable_statistics has not been set to True
00097 """
00098
00099 if not rospy.get_param('/enable_statistics', False):
00100 raise rospy.ROSInitException("Rosparam '/enable_statistics' has not been set to true. Aborting")
00101
00102 if self._monitor_timer is not None:
00103 raise Exception("Monitor Timer already started!")
00104 if self._graphupdate_timer is not None:
00105 raise Exception("Graph Update Timer already started!")
00106 if self._publisher_timer is not None:
00107 raise Exception("Publisher Timer already started!")
00108
00109
00110 self._update_node_list()
00111
00112 for node in self._nodes.values():
00113 node.reset()
00114
00115 self._monitor_timer = rospy.Timer(self.sample_rate, self._collect_data)
00116 self._publisher_timer = rospy.Timer(self.update_rate, self._publish_data)
00117 self._graphupdate_timer = rospy.Timer(self.update_rate, self._update_node_list)
00118
00119 def stop(self):
00120 timers = [self._monitor_timer, self._publisher_timer, self._graphupdate_timer]
00121 timers = [timer for timer in timers if timer is not None]
00122 for timer in timers:
00123 timer.shutdown()
00124 for timer in timers:
00125 timer.join()
00126
00127 def _update_node_list(self, event=None):
00128 """ Contacts the master using xmlrpc to determine what processes to watch """
00129 nodenames = rosnode.get_nodes_by_machine(rosgraph.network.get_host_name())
00130
00131 with self._lock:
00132
00133 for name in self._nodes.keys():
00134 if not self._nodes[name].is_running():
00135 rospy.loginfo("Removing Monitor for '%s'" % name)
00136 self._nodes.pop(name)
00137
00138 for name in nodenames:
00139 if name not in self._nodes:
00140 rospy.loginfo("Adding Monitor for '%s'" % name)
00141 try:
00142 uri = self._master.lookupNode(name)
00143 code, msg, pid = xmlrpclib.ServerProxy(uri).getPid('/NODEINFO')
00144 node = NodeMonitor(name, uri, pid)
00145 except rosgraph.masterapi.MasterError:
00146 rospy.logerr("WARNING: MasterAPI Error trying to contact '%s', skipping" % name)
00147 continue
00148 except xmlrpclib.socket.error:
00149 rospy.logerr("WANRING: XML RPC ERROR contacting '%s', skipping" % name)
00150 continue
00151 self._nodes[name] = node
00152
00153 def _collect_data(self, event=None):
00154 """ Collects data about the host and nodes """
00155 with self._lock:
00156
00157 self._host_monitor.update()
00158
00159 for node in self._nodes.values():
00160 if node.is_running():
00161 node.update()
00162
00163 def _publish_data(self, event=None):
00164 """ Publishes data about the host and processing running on it. """
00165 with self._lock:
00166 rospy.logdebug("Publish data")
00167
00168 self._host_publisher.publish(self._host_monitor.get_statistics())
00169 self._host_monitor.reset()
00170
00171
00172 for node in self._nodes.values():
00173 self._node_publisher.publish(node.get_statistics())
00174 node.reset()