31 from xmlrpc.client
import ServerProxy
33 from xmlrpclib
import ServerProxy
34 from socket
import error
as SocketError
44 node_api = rosnode.get_api_uri(rospy.get_master(), node_name, skip_cache=skip_cache)
46 code, msg, pid = ServerProxy(node_api[2]).getPid(ID)
47 if node_name
in self.
nodes:
48 return self.
nodes[node_name]
51 p = psutil.Process(pid)
52 self.
nodes[node_name] = p
65 for node_name
in rosnode.get_node_names():
68 infos.append((node_name, info))
74 psutil_v2_api = int(psutil.__version__.split(
'.')[0]) >= 2
75 for name, p
in processes:
76 all_fields = fields + [
'cmdline',
'get_memory_info']
79 f[4:]
if f.startswith(
'get_')
else f
81 infos.append(self.
as_dict(p, all_fields))
82 infos[-1][
'node_name'] = name
86 running_nodes = rosnode.get_node_names()
87 dead_nodes = [node_name
for node_name
in self.
nodes if node_name
not in running_nodes]
88 for node_name
in dead_nodes:
89 self.nodes.pop(node_name,
None)
92 success, fail = rosnode.kill_nodes([node_name])
93 return node_name
in success
95 def as_dict(self, p, attrs=[], ad_value=None):
97 excluded_names = set([
'send_signal',
'suspend',
'resume',
'terminate',
98 'kill',
'wait',
'is_running',
'as_dict',
'parent',
99 'get_children',
'nice'])
101 for name
in set(attrs
or dir(p)):
102 if name.startswith(
'_'):
104 if name.startswith(
'set_'):
106 if name
in excluded_names:
109 attr = getattr(p, name)
111 if name ==
'get_cpu_percent':
112 ret = attr(interval=0)
117 except psutil.AccessDenied:
119 except NotImplementedError:
126 if name.startswith(
'get'):
129 elif name ==
'getcwd':
def kill_node(self, node_name)
def remove_dead_nodes(self)
def get_node_info(self, node_name, skip_cache=False)
def as_dict(self, p, attrs=[], ad_value=None)
def get_all_node_fields(self, fields)
def get_all_node_info(self)