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 class NodeInfo(object):
00040 nodes = dict()
00041
00042 def get_node_info(self, node_name, skip_cache=False):
00043 node_api = rosnode.get_api_uri(rospy.get_master(), node_name, skip_cache=skip_cache)
00044 try:
00045 code, msg, pid = ServerProxy(node_api[2]).getPid(ID)
00046 if node_name in self.nodes:
00047 return self.nodes[node_name]
00048 else:
00049 try:
00050 p = psutil.Process(pid)
00051 self.nodes[node_name] = p
00052 return p
00053 except:
00054 return False
00055 except SocketError:
00056 if not skip_cache:
00057 return self.get_node_info(node_name, skip_cache=True)
00058 else:
00059 return False
00060
00061 def get_all_node_info(self):
00062 infos = []
00063 self.remove_dead_nodes()
00064 for node_name in rosnode.get_node_names():
00065 info = self.get_node_info(node_name)
00066 if info is not False: infos.append((node_name, info))
00067 return infos
00068
00069 def get_all_node_fields(self, fields):
00070 processes = self.get_all_node_info()
00071 infos = []
00072 psutil_v2_api = int(psutil.__version__.split('.')[0]) >= 2
00073 for name, p in processes:
00074 all_fields = fields + ['cmdline', 'get_memory_info']
00075 if psutil_v2_api:
00076 all_fields = [
00077 f[4:] if f.startswith('get_') else f
00078 for f in all_fields]
00079 infos.append(self.as_dict(p, all_fields))
00080 infos[-1]['node_name'] = name
00081 return infos
00082
00083 def remove_dead_nodes(self):
00084 running_nodes = rosnode.get_node_names()
00085 dead_nodes = [node_name for node_name in self.nodes if node_name not in running_nodes]
00086 for node_name in dead_nodes:
00087 self.nodes.pop(node_name, None)
00088
00089 def kill_node(self, node_name):
00090 success, fail = rosnode.kill_nodes([node_name])
00091 return node_name in success
00092
00093 def as_dict(self, p, attrs=[], ad_value=None):
00094
00095 excluded_names = set(['send_signal', 'suspend', 'resume', 'terminate',
00096 'kill', 'wait', 'is_running', 'as_dict', 'parent',
00097 'get_children', 'nice'])
00098 retdict = dict()
00099 for name in set(attrs or dir(p)):
00100 if name.startswith('_'):
00101 continue
00102 if name.startswith('set_'):
00103 continue
00104 if name in excluded_names:
00105 continue
00106 try:
00107 attr = getattr(p, name)
00108 if callable(attr):
00109 if name == 'get_cpu_percent':
00110 ret = attr(interval=0)
00111 else:
00112 ret = attr()
00113 else:
00114 ret = attr
00115 except psutil.AccessDenied:
00116 ret = ad_value
00117 except NotImplementedError:
00118
00119
00120
00121 if attrs:
00122 raise
00123 continue
00124 if name.startswith('get'):
00125 if name[3] == '_':
00126 name = name[4:]
00127 elif name == 'getcwd':
00128 name = 'cwd'
00129 retdict[name] = ret
00130 return retdict