Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 import rosnode
00029 import rospy
00030 try:
00031 from xmlrpc.client import ServerProxy
00032 except ImportError:
00033 from xmlrpclib import ServerProxy
00034 from socket import error as SocketError
00035 import psutil
00036
00037 ID = '/NODEINFO'
00038
00039
00040 class NodeInfo(object):
00041 nodes = dict()
00042
00043 def get_node_info(self, node_name, skip_cache=False):
00044 node_api = rosnode.get_api_uri(rospy.get_master(), node_name, skip_cache=skip_cache)
00045 try:
00046 code, msg, pid = ServerProxy(node_api[2]).getPid(ID)
00047 if node_name in self.nodes:
00048 return self.nodes[node_name]
00049 else:
00050 try:
00051 p = psutil.Process(pid)
00052 self.nodes[node_name] = p
00053 return p
00054 except:
00055 return False
00056 except SocketError:
00057 if not skip_cache:
00058 return self.get_node_info(node_name, skip_cache=True)
00059 else:
00060 return False
00061
00062 def get_all_node_info(self):
00063 infos = []
00064 self.remove_dead_nodes()
00065 for node_name in rosnode.get_node_names():
00066 info = self.get_node_info(node_name)
00067 if info is not False:
00068 infos.append((node_name, info))
00069 return infos
00070
00071 def get_all_node_fields(self, fields):
00072 processes = self.get_all_node_info()
00073 infos = []
00074 psutil_v2_api = int(psutil.__version__.split('.')[0]) >= 2
00075 for name, p in processes:
00076 all_fields = fields + ['cmdline', 'get_memory_info']
00077 if psutil_v2_api:
00078 all_fields = [
00079 f[4:] if f.startswith('get_') else f
00080 for f in all_fields]
00081 infos.append(self.as_dict(p, all_fields))
00082 infos[-1]['node_name'] = name
00083 return infos
00084
00085 def remove_dead_nodes(self):
00086 running_nodes = rosnode.get_node_names()
00087 dead_nodes = [node_name for node_name in self.nodes if node_name not in running_nodes]
00088 for node_name in dead_nodes:
00089 self.nodes.pop(node_name, None)
00090
00091 def kill_node(self, node_name):
00092 success, fail = rosnode.kill_nodes([node_name])
00093 return node_name in success
00094
00095 def as_dict(self, p, attrs=[], ad_value=None):
00096
00097 excluded_names = set(['send_signal', 'suspend', 'resume', 'terminate',
00098 'kill', 'wait', 'is_running', 'as_dict', 'parent',
00099 'get_children', 'nice'])
00100 retdict = dict()
00101 for name in set(attrs or dir(p)):
00102 if name.startswith('_'):
00103 continue
00104 if name.startswith('set_'):
00105 continue
00106 if name in excluded_names:
00107 continue
00108 try:
00109 attr = getattr(p, name)
00110 if callable(attr):
00111 if name == 'get_cpu_percent':
00112 ret = attr(interval=0)
00113 else:
00114 ret = attr()
00115 else:
00116 ret = attr
00117 except psutil.AccessDenied:
00118 ret = ad_value
00119 except NotImplementedError:
00120
00121
00122
00123 if attrs:
00124 raise
00125 continue
00126 if name.startswith('get'):
00127 if name[3] == '_':
00128 name = name[4:]
00129 elif name == 'getcwd':
00130 name = 'cwd'
00131 retdict[name] = ret
00132 return retdict