node_info.py
Go to the documentation of this file.
1 # Copyright (c) 2013, Oregon State University
2 # All rights reserved.
3 
4 # Redistribution and use in source and binary forms, with or without
5 # modification, are permitted provided that the following conditions are met:
6 # * Redistributions of source code must retain the above copyright
7 # notice, this list of conditions and the following disclaimer.
8 # * Redistributions in binary form must reproduce the above copyright
9 # notice, this list of conditions and the following disclaimer in the
10 # documentation and/or other materials provided with the distribution.
11 # * Neither the name of the Oregon State University nor the
12 # names of its contributors may be used to endorse or promote products
13 # derived from this software without specific prior written permission.
14 
15 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
16 # ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
17 # WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
18 # DISCLAIMED. IN NO EVENT SHALL OREGON STATE UNIVERSITY BE LIABLE FOR ANY
19 # DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
20 # (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
21 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
22 # ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
23 # (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
24 # SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
25 
26 # Author Dan Lazewatsky/lazewatd@engr.orst.edu
27 
28 import rosnode
29 import rospy
30 try:
31  from xmlrpc.client import ServerProxy
32 except ImportError:
33  from xmlrpclib import ServerProxy
34 from socket import error as SocketError
35 import psutil
36 
37 ID = '/NODEINFO'
38 
39 
40 class NodeInfo(object):
41  nodes = dict()
42 
43  def get_node_info(self, node_name, skip_cache=False):
44  node_api = rosnode.get_api_uri(rospy.get_master(), node_name, skip_cache=skip_cache)
45  try:
46  code, msg, pid = ServerProxy(node_api[2]).getPid(ID)
47  if node_name in self.nodes:
48  return self.nodes[node_name]
49  else:
50  try:
51  p = psutil.Process(pid)
52  self.nodes[node_name] = p
53  return p
54  except:
55  return False
56  except SocketError:
57  if not skip_cache:
58  return self.get_node_info(node_name, skip_cache=True)
59  else:
60  return False
61 
62  def get_all_node_info(self):
63  infos = []
64  self.remove_dead_nodes()
65  for node_name in rosnode.get_node_names():
66  info = self.get_node_info(node_name)
67  if info is not False:
68  infos.append((node_name, info))
69  return infos
70 
71  def get_all_node_fields(self, fields):
72  processes = self.get_all_node_info()
73  infos = []
74  psutil_v2_api = int(psutil.__version__.split('.')[0]) >= 2
75  for name, p in processes:
76  all_fields = fields + ['cmdline', 'get_memory_info']
77  if psutil_v2_api:
78  all_fields = [
79  f[4:] if f.startswith('get_') else f
80  for f in all_fields]
81  infos.append(self.as_dict(p, all_fields))
82  infos[-1]['node_name'] = name
83  return infos
84 
85  def remove_dead_nodes(self):
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)
90 
91  def kill_node(self, node_name):
92  success, fail = rosnode.kill_nodes([node_name])
93  return node_name in success
94 
95  def as_dict(self, p, attrs=[], ad_value=None):
96  # copied code from psutil.__init__ from a newer version
97  excluded_names = set(['send_signal', 'suspend', 'resume', 'terminate',
98  'kill', 'wait', 'is_running', 'as_dict', 'parent',
99  'get_children', 'nice'])
100  retdict = dict()
101  for name in set(attrs or dir(p)):
102  if name.startswith('_'):
103  continue
104  if name.startswith('set_'):
105  continue
106  if name in excluded_names:
107  continue
108  try:
109  attr = getattr(p, name)
110  if callable(attr):
111  if name == 'get_cpu_percent':
112  ret = attr(interval=0)
113  else:
114  ret = attr()
115  else:
116  ret = attr
117  except psutil.AccessDenied:
118  ret = ad_value
119  except NotImplementedError:
120  # in case of not implemented functionality (may happen
121  # on old or exotic systems) we want to crash only if
122  # the user explicitly asked for that particular attr
123  if attrs:
124  raise
125  continue
126  if name.startswith('get'):
127  if name[3] == '_':
128  name = name[4:]
129  elif name == 'getcwd':
130  name = 'cwd'
131  retdict[name] = ret
132  return retdict
def kill_node(self, node_name)
Definition: node_info.py:91
def get_node_info(self, node_name, skip_cache=False)
Definition: node_info.py:43
def as_dict(self, p, attrs=[], ad_value=None)
Definition: node_info.py:95
def get_all_node_fields(self, fields)
Definition: node_info.py:71


rqt_top
Author(s): Dan Lazewatsky
autogenerated on Sat Jun 8 2019 04:43:00