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