__init__.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 import os
4 import sys
5 import socket
6 import re
7 import time
8 import yaml
9 # Fast zip compatibility with Python 2 and 3
10 try:
11  from itertools import izip as zip
12 except ImportError:
13  pass
14 
15 from optparse import OptionParser
16 import rosgraph
17 import rostopic
18 import rospy
19 import genpy
20 from marti_introspection_msgs.msg import NodeInfo, TopicInfo, ParamInfo, ServiceInfo
21 
22 DOCUMENTATION_TOPIC_MATCHER = re.compile("/documentation$")
23 
24 def _check_master(rosmaster):
25  try:
26  rosmaster.getPid()
27  except socket.error:
28  # Stealing rostopics exception type for now
29  raise rostopic.ROSTopicIOException("Unable to communicate with master!")
30 
31 def _sort_fn(e):
32  return e.name
33 
35  def __init__(self, rosmaster):
36  self.rosmaster = rosmaster
37  self.callback_called = False
38  self.last_doc_msg = None
39  # Setup a node to read topics with
41  rospy.init_node('rosman', anonymous=True)
42 
43  def doc_topic_callback(self, doc_msg):
44  self.last_doc_msg = doc_msg
45  self.callback_called = True
46 
47  def read_doc_topic(self, topic, timeout_duration=2.0):
48  self.callback_called = False
49  doc_sub = rospy.Subscriber(topic, NodeInfo, self.doc_topic_callback)
50  timeout = time.time()+timeout_duration
51  while time.time() < timeout and self.callback_called == False and \
52  not rospy.is_shutdown():
53  rospy.rostime.wallsleep(0.1)
54  if not self.callback_called:
55  self.last_doc_msg = None
56  # Let caller know if reading was successful
57  return self.callback_called
58 
59  def write_node_documentation(self, output_file=sys.stdout):
60  # TODO error out correctly if the last topic wasn't read correctly
61  if (self.last_doc_msg is None):
62  print('DocTopicReader failed to read documentation topic and cannot write out the node documentation')
63  return
64 
65  # sort things
66  self.last_doc_msg.topics.sort(key=_sort_fn)
67  self.last_doc_msg.parameters.sort(key=_sort_fn)
68  self.last_doc_msg.services.sort(key=_sort_fn)
69 
70  # output the overall header
71  self.write_node_header_documentation(output_file)
72 
73  # divide by grouping then print for each group, starting with empty
74  groups = {}
75  for item in self.last_doc_msg.topics:
76  if item.group not in groups:
77  groups[item.group] = NodeInfo()
78  groups[item.group].topics.append(item)
79 
80  for item in self.last_doc_msg.parameters:
81  if item.group not in groups:
82  groups[item.group] = NodeInfo()
83  groups[item.group].parameters.append(item)
84 
85  for item in self.last_doc_msg.services:
86  if item.group not in groups:
87  groups[item.group] = NodeInfo()
88  groups[item.group].services.append(item)
89 
90  # output the empty group first
91  self.write_node_subscriptions_documentation(output_file, groups[""])
92  self.write_node_publishers_documentation(output_file, groups[""])
93  self.write_node_parameters_documentation(output_file, groups[""])
94  self.write_node_services_documentation(output_file, groups[""])
95 
96  for group in groups:
97  if group == "":
98  continue
99 
100  output_file.write("\n\nGroup: {name}\n\n".format(name=group))
101 
102  self.write_node_subscriptions_documentation(output_file, groups[group])
103  self.write_node_publishers_documentation(output_file, groups[group])
104  self.write_node_parameters_documentation(output_file, groups[group])
105  self.write_node_services_documentation(output_file, groups[group])
106 
107 
108  def write_node_header_documentation(self, output_file=sys.stdout):
109  output_file.write("{name} - ({nodelet_manager})\n{description}\n\n".format(name=self.last_doc_msg.name,
110  nodelet_manager=self.last_doc_msg.nodelet_manager,
111  description=self.last_doc_msg.description if self.last_doc_msg.description else "TODO: node description"))
112 
113  def write_node_subscriptions_documentation(self, output_file, data):
114  output_file.write("Subscriptions:\n")
115  subs = [topic for topic in data.topics if topic.advertised == False]
116  for sub in subs:
117  output_file.write(' * ')
118  self.write_topic_info_docstring(sub, output_file)
119  output_file.write('\n')
120 
121  def write_topic_info_docstring(self, topic_info_msg, output_file=sys.stdout):
122  output_file.write("{name} - ({type}) - {description}\n".format(name=topic_info_msg.name,
123  type=topic_info_msg.message_type,
124  description=topic_info_msg.description))
125 
126  def write_node_publishers_documentation(self, output_file, data):
127  output_file.write("Publishers:\n")
128  pubs = [topic for topic in data.topics if topic.advertised == True]
129  for pub in pubs:
130  output_file.write(' * ')
131  self.write_topic_info_docstring(pub, output_file)
132  output_file.write('\n')
133 
134  def write_node_parameters_documentation(self, output_file, data):
135  if len(self.last_doc_msg.parameters) > 0:
136  output_file.write("Parameters:\n")
137  for param in data.parameters:
138  output_file.write(' * ')
139  self.write_param_info_docstring(param, output_file)
140  output_file.write('\n')
141 
142  def write_node_services_documentation(self, output_file, data):
143  servs = [service for service in data.services if service.server == True]
144  if len(servs) > 0:
145  output_file.write("Service Servers:\n")
146  for serv in servs:
147  output_file.write(' * ')
148  self.write_service_info_docstring(serv, output_file=sys.stdout)
149  output_file.write('\n')
150 
151  servs = [service for service in data.services if service.server == False]
152  if len(servs) > 0:
153  output_file.write("Service Clients:\n")
154  for serv in servs:
155  output_file.write(' * ')
156  self.write_service_info_docstring(serv, output_file=sys.stdout)
157  output_file.write('\n')
158 
159  def write_param_info_docstring(self, param_info_msg, output_file=sys.stdout):
160  default_val = ""
161  type_str = "unknown_type"
162  if (param_info_msg.type == ParamInfo.TYPE_DOUBLE):
163  default_val = param_info_msg.default_double
164  type_str = "double"
165  if param_info_msg.max_value != param_info_msg.min_value:
166  output_file.write("{name} - ({type}, {min:.6g} <= {default:.6g} <= {max:.6g}) - {description}\n".format(name=param_info_msg.name,
167  type=type_str, default=default_val, description=param_info_msg.description, max=param_info_msg.max_value, min=param_info_msg.min_value))
168  else:
169  output_file.write("{name} - ({type}, {default:.6g}) - {description}\n".format(name=param_info_msg.name,
170  type=type_str, default=default_val, description=param_info_msg.description))
171  return
172  elif (param_info_msg.type == ParamInfo.TYPE_STRING):
173  default_val = param_info_msg.default_string
174  type_str = "string"
175  output_file.write("{name} - ({type}, {default}) - {description}\n".format(name=param_info_msg.name,
176  type=type_str, default=default_val, description=param_info_msg.description))
177  return
178  elif (param_info_msg.type == ParamInfo.TYPE_INT):
179  default_val = param_info_msg.default_int
180  type_str = "int"
181  output_file.write("{name} - ({type}, {default:d}) - {description}\n".format(name=param_info_msg.name,
182  type=type_str, default=default_val, description=param_info_msg.description))
183  return
184  elif (param_info_msg.type == ParamInfo.TYPE_FLOAT):
185  default_val = param_info_msg.default_float
186  type_str = "float"
187  if param_info_msg.max_value != param_info_msg.min_value:
188  output_file.write("{name} - ({type}, {min:.6g} <= {default:.6g} <= {max:.6g}) - {description}\n".format(name=param_info_msg.name,
189  type=type_str, default=default_val, description=param_info_msg.description, max=param_info_msg.max_value, min=param_info_msg.min_value))
190  else:
191  output_file.write("{name} - ({type}, {default:.6g}) - {description}\n".format(name=param_info_msg.name,
192  type=type_str, default=default_val, description=param_info_msg.description))
193  return
194  elif (param_info_msg.type == ParamInfo.TYPE_BOOL):
195  default_val = "true" if param_info_msg.default_bool else "false"
196  type_str = "bool"
197  output_file.write("{name} - ({type}, {default}) - {description}\n".format(name=param_info_msg.name,
198  type=type_str, default=default_val, description=param_info_msg.description))
199  return
200  elif (param_info_msg.type == ParamInfo.TYPE_XMLRPC):
201  type_str = "XMLRPC"
202  output_file.write("{name} - ({type}) - {description}\n".format(name=param_info_msg.name,
203  type=type_str, description=param_info_msg.description))
204  return
205  # Unknown type write
206  output_file.write("{name} - ({type}, {default}) - {description}\n".format(name=param_info_msg.name,
207  type=type_str, default=default_val, description=param_info_msg.description))
208 
209 
210  def write_service_info_docstring(self, service_info_msg, output_file=sys.stdout):
211  output_file.write("{name} - ({type}) - {description}\n".format(name=service_info_msg.name,
212  type=service_info_msg.message_type, description=service_info_msg.description))
213 
214  def get_doc_msg_topic(self, input_topic):
215  if self.last_doc_msg is None:
216  return False
217  for doc_topic in self.last_doc_msg.topics:
218  if doc_topic.resolved_name == input_topic:
219  return doc_topic
220  return False
221 
222  def get_doc_msg_param(self, input_param):
223  if self.last_doc_msg is None:
224  return False
225  for doc_param in self.last_doc_msg.parameters:
226  if doc_param.resolved_name == input_param:
227  return doc_param
228  return False
229 
230  def get_doc_msg_service(self, input_service):
231  if self.last_doc_msg is None:
232  return False
233  for doc_service in self.last_doc_msg.services:
234  if doc_service.resolved_name == input_service:
235  return doc_service
236  return False
237 
238 def read_documentation_topic(rosmaster, topic, yaml=False, output_file=sys.stdout):
239  topic_reader = DocTopicReader(rosmaster)
240  if topic_reader.read_doc_topic(topic):
241  if yaml:
242  output_file.write(genpy.message.strify_message(topic_reader.last_doc_msg) + '\n')
243  else:
244  topic_reader.write_node_documentation(output_file)
245 
246 def get_documentation_publications(rosmaster, ros_sys_state=None):
247  """
248  Get all the current documentation topics in the system
249  """
250  # get the master system state if not passed in by caller
251  if ros_sys_state is None:
252  try:
253  ros_sys_state = rosmaster.getSystemState()
254  except socket.error:
255  print('Could not communicate with ROS master!')
256  sys.exit(2)
257  pubs, _, _ = ros_sys_state
258  doc_topics = []
259  doc_node_namespaces = []
260  doc_publisher_nodes = []
261  for t, n in pubs:
262  doc_match = DOCUMENTATION_TOPIC_MATCHER.search(t)
263  if doc_match:
264  # Try stripping the node namespace off the topic
265  node_namespace = t[0:doc_match.span()[0]]
266  doc_topics.append(t)
267  doc_node_namespaces.append(node_namespace)
268  doc_publisher_nodes.append(n)
269  #print('node {0} with node namespace {1} publishes topic {2}'.format(n, node_namespace ,t))
270  return doc_topics, doc_node_namespaces, doc_publisher_nodes
271 
272 def rosman_node(rosmaster, node_name, yaml=False, output_file=sys.stdout):
273  # The doc_node_namespaces are probably the more accurate "node" information for the documentation topic
274  # since the doc_publisher nodes for a doc topic can be a nodelet manager
275  documentation_info = get_documentation_publications(rosmaster)
276  node_documentation_found = False
277  for topic, node_namespace, publishers in zip(documentation_info[0], documentation_info[1], documentation_info[2]):
278  if node_namespace in node_name or node_name in publishers:
279  read_documentation_topic(rosmaster, topic, yaml=yaml, output_file=output_file)
280  node_documentation_found = True
281  return node_documentation_found
282 
283 def rosman_node_fallback(rosmaster, node_name, yaml=False, output_file=sys.stdout):
284  # TODO figure out if we need to support other options in fallback?
285  # if yaml:
286  # print('YAML output not supported for rosman node fallback documentation!')
287  # yaml = False
288  if output_file is not sys.stdout:
289  print('Output other than stdout not support for rosman node fallback documentation!')
290  output_file = sys.stdout
291 
292  def topic_type(t, pub_topics):
293  matches = [t_type for t_name, t_type in pub_topics if t_name == t]
294  if matches:
295  return matches[0]
296  return 'unknown type'
297 
298  def param_type(param_value):
299  if isinstance(param_value, float):
300  # Can't really distinguish between float and double
301  return ParamInfo.TYPE_DOUBLE
302  elif isinstance(param_value, str):
303  return ParamInfo.TYPE_STRING
304  elif isinstance(param_value, int):
305  return ParamInfo.TYPE_INT
306  elif isinstance(param_value, bool):
307  return ParamInfo.TYPE_BOOL
308  else:
309  # Reasonable failure fallback?
310  return ParamInfo.TYPE_STRING
311  try:
312  ros_sys_state = rosmaster.getSystemState()
313  pub_topics = rosmaster.getPublishedTopics('/')
314  # param_list_success, _, param_list = rosmaster.getParamNames()
315  param_list = rosmaster.getParamNames()
316  except socket.error:
317  print('Could not communicate with ROS master!')
318  sys.exit(2)
319  pubs = sorted([t for t, l in ros_sys_state[0] if node_name in l])
320  subs = sorted([t for t, l in ros_sys_state[1] if node_name in l])
321  srvs = sorted([t for t, l in ros_sys_state[2] if node_name in l])
322  # This will only retrieve private parameters for this node, but better than nothing
323  params = sorted([p for p in param_list if p.startswith(node_name)])
324 
325  # Fill out a shim node documentation and hack the DocTopicReader to write output
326  doc = NodeInfo()
327  doc.name = node_name
328  doc.description = 'Warning: no documentation topic is published for {n}. Falling back to standard rosnode info.'.format(n=node_name)
329  for pub in pubs:
330  topic_doc = TopicInfo()
331  topic_doc.name = pub
332  topic_doc.resolved_name = pub
333  topic_doc.message_type = topic_type(pub, pub_topics)
334  topic_doc.advertised = True
335  doc.topics.append(topic_doc)
336  for sub in subs:
337  topic_doc = TopicInfo()
338  topic_doc.name = sub
339  topic_doc.resolved_name = sub
340  topic_doc.message_type = topic_type(sub, pub_topics)
341  topic_doc.advertised = False
342  doc.topics.append(topic_doc)
343  for param in params:
344  param_doc = ParamInfo()
345  param_doc.name = param.replace(node_name, '')
346  if param_doc.name[0] == '/':
347  param_doc.name = param_doc.name[1:]
348  param_doc.resolved_name = param
349  param_val = rosmaster.getParam(param)
350  param_doc.type = param_type(param_val)
351  if param_doc.type == ParamInfo.TYPE_DOUBLE:
352  param_doc.default_double = float(param_val)
353  elif param_doc.type == ParamInfo.TYPE_STRING:
354  param_doc.default_string = str(param_val)
355  elif param_doc.type == ParamInfo.TYPE_INT:
356  param_doc.default_int = int(param_val)
357  elif param_doc.type == ParamInfo.TYPE_BOOL:
358  param_doc.default_bool = bool(param_val)
359  doc.parameters.append(param_doc)
360  for srv in srvs:
361  if not (srv.endswith('get_loggers') or srv.endswith('set_logger_level')):
362  srv_doc = ServiceInfo()
363  srv_doc.name = srv
364  srv_doc.resolved_name = srv
365  # TODO get service type info
366  srv_doc.message_type = 'unknown type'
367  srv_doc.server = True
368  doc.services.append(srv_doc)
369  topic_reader = DocTopicReader(rosmaster)
370  topic_reader.last_doc_msg = doc
371  if yaml:
372  output_file.write(genpy.message.strify_message(doc) + '\n')
373  else:
374  topic_reader.write_node_documentation(output_file)
375 
376 
377 def rosman_topic(rosmaster, topic):
378  # Find the desired topic in the list of publishers from the system state
379  try:
380  ros_sys_state = rosmaster.getSystemState()
381  except socket.error:
382  print('Could not communicate with ROS master!')
383  sys.exit(2)
384  pubs, subs, _ = ros_sys_state
385  topic_documentation_found = False
386  for t, publisher_nodes in pubs:
387  if t == topic:
388  for node in publisher_nodes:
389  # print('Found topic: {t} published by node: {n}'.format(t=t, n=node))
390  doc_info = get_documentation_publications(rosmaster, ros_sys_state)
391  for doc_topic, doc_pub_namespace, doc_pubs in zip(doc_info[0], doc_info[1], doc_info[2]):
392  if node in doc_pub_namespace or node in doc_pubs:
393  # print('Found {node} in namespace {ns} or doc publishers {dp}'.format(node=node, ns=doc_pub_namespace, dp=doc_pubs))
394  topic_reader = DocTopicReader(rosmaster)
395  if topic_reader.read_doc_topic(doc_topic):
396  topic_doc = topic_reader.get_doc_msg_topic(topic)
397  if topic_doc:
398  topic_reader.write_node_header_documentation()
399  topic_reader.write_topic_info_docstring(topic_doc)
400  topic_documentation_found = True
401 
402  # Find subscribers if there are no publishers
403  for t, subscriber_nodes in subs:
404  if t == topic:
405  for node in subscriber_nodes:
406  # print('Found topic: {t} published by node: {n}'.format(t=t, n=node))
407  doc_info = get_documentation_publications(rosmaster, ros_sys_state)
408  for doc_topic, doc_pub_namespace, doc_pubs in zip(doc_info[0], doc_info[1], doc_info[2]):
409  if node in doc_pub_namespace or node in doc_pubs:
410  # print('Found {node} in namespace {ns} or doc publishers {dp}'.format(node=node, ns=doc_pub_namespace, dp=doc_pubs))
411  topic_reader = DocTopicReader(rosmaster)
412  if topic_reader.read_doc_topic(doc_topic):
413  topic_doc = topic_reader.get_doc_msg_topic(topic)
414  if topic_doc and not topic_documentation_found:
415  topic_reader.write_node_header_documentation()
416  topic_reader.write_topic_info_docstring(topic_doc)
417  topic_documentation_found = True
418 
419  if topic_documentation_found == False:
420  print('Could not find published documentation for topic: {t}'.format(t=topic))
421 
422 def rosman_param(rosmaster, param):
423  param_documentation_found = False
424  doc_topics, doc_node_namespaces, doc_publishers = get_documentation_publications(rosmaster)
425  topic_reader = DocTopicReader(rosmaster)
426  for doc_topic in doc_topics:
427  if topic_reader.read_doc_topic(doc_topic):
428  param_doc = topic_reader.get_doc_msg_param(param)
429  if param_doc:
430  topic_reader.write_node_header_documentation()
431  topic_reader.write_param_info_docstring(param_doc)
432  param_documentation_found = True
433  if param_documentation_found == False:
434  print('Could not find published documentation for parameter: {p}'.format(p=param))
435 
436 def rosman_service(rosmaster, service):
437  service_documentation_found = False
438  doc_topics, _, _ = get_documentation_publications(rosmaster)
439  topic_reader = DocTopicReader(rosmaster)
440  for doc_topic in doc_topics:
441  if topic_reader.read_doc_topic(doc_topic):
442  service_doc = topic_reader.get_doc_msg_service(service)
443  if service_doc and service_doc.server:
444  topic_reader.write_node_header_documentation()
445  topic_reader.write_service_info_docstring(service_doc)
446  service_documentation_found = True
447 
448  # If still not found, check clients
449  for doc_topic in doc_topics:
450  if topic_reader.read_doc_topic(doc_topic):
451  service_doc = topic_reader.get_doc_msg_service(service)
452  if service_doc and not service_doc.server and not service_documentation_found:
453  topic_reader.write_node_header_documentation()
454  topic_reader.write_service_info_docstring(service_doc)
455  service_documentation_found = True
456  if service_documentation_found == False:
457  print('Could not find published documentation for service: {s}'.format(s=service))
458 
460  """
461  Entry point for rosman node command
462  """
463  args = argv[2:]
464  parser = OptionParser(usage='usage: %prog node node1 [node2...]')
465  parser.add_option('-y','--yaml', dest="yaml", action="store_true",
466  default=False, help='print node documentation output as a yaml compliant string')
467  parser.add_option('-f', '--filename', dest="filename", action="store",
468  metavar="FILE", help="write output to FILE. If the file exists, the output will be appended, otherwise a new file with the name FILE will be created.")
469  (options, args) = parser.parse_args(args)
470 
471  if not args:
472  parser.error('You must specify at least one node name')
473 
474  ros_master = rosgraph.Master('/rosman')
475  if options.filename:
476  with open(options.filename, 'a') as output_file:
477  for node in args:
478  if not rosman_node(ros_master, node, yaml=options.yaml, output_file=output_file):
479  rosman_node_fallback(ros_master, node, yaml=options.yaml, output_file=output_file)
480  else:
481  # Write all to stdout
482  for node in args:
483  if not rosman_node(ros_master, node, yaml=options.yaml):
484  rosman_node_fallback(ros_master, node, yaml=options.yaml)
485 
487  """
488  Entry point for rosman check command
489  """
490  args = argv[2:]
491  parser = OptionParser(usage='usage: %prog node node1 [node2...]')
492  parser.add_option('-y','--yaml', dest="yaml", action="store_true",
493  default=False, help='print node documentation output as a yaml compliant string')
494  parser.add_option('-f', '--filename', dest="filename", action="store",
495  metavar="FILE", help="write output to FILE. If the file exists, the output will be appended, otherwise a new file with the name FILE will be created.")
496  parser.add_option("-v", action="store_true", dest="reverse")
497  (options, args) = parser.parse_args(args)
498 
499  if not args:
500  parser.error('You must specify at least one node name')
501 
502  ros_master = rosgraph.Master('/rosman')
503 
504  # Write all to stdout
505  for node in args:
506  compare_param(ros_master, node, yaml=options.yaml, reverse=options.reverse)
507 
508 def compare_param(rosmaster, node_name, yaml=False, output_file=sys.stdout, reverse=False):
509  doc_server_array = []
510  param_server_array = []
511  unused_param = []
512 
513  documentation_info = get_documentation_publications(rosmaster)
514  print("\n--------------------------------------------------------------------------------\nNode [" + node_name + "]")
515  for topic, node_namespace, publishers in zip(documentation_info[0], documentation_info[1], documentation_info[2]):
516  if node_namespace in node_name or node_name in publishers:
517  topic_reader = DocTopicReader(rosmaster)
518  if topic_reader.read_doc_topic(topic):
519  # TODO error out correctly if the last topic wasn't read correctly
520  if (topic_reader.last_doc_msg is None):
521  print('DocTopicReader failed to read documentation topic and cannot write out the node documentation')
522  return
523  # sort things
524  topic_reader.last_doc_msg.parameters.sort(key=_sort_fn)
525  # divide by grouping then print for each group, starting with empty
526  groups = {}
527 
528  for item in topic_reader.last_doc_msg.parameters:
529  if item.group not in groups:
530  groups[item.group] = NodeInfo()
531  groups[item.group].parameters.append(item)
532 
533  data = groups[""]
534  if len(topic_reader.last_doc_msg.parameters) > 0:
535  #print("DOCUMENTED:\n")
536  for param in data.parameters:
537  #print(param.resolved_name)
538  doc_server_array.append(param.resolved_name)
539 
540  for group in groups:
541  if group == "":
542  continue
543  data = groups[group]
544  if len(topic_reader.last_doc_msg.parameters) > 0:
545  for param in data.parameters:
546  #print(param.resolved_name)
547  doc_server_array.append(param.resolved_name)
548  if not doc_server_array:
549  print("Warning: no documentation topic is published for " + node_name + " Falling back to standard rosnode info.\n")
550  return
551 
552  try:
553  ros_sys_state = rosmaster.getSystemState()
554  param_list = rosmaster.getParamNames() #array
555  except socket.error:
556  print('Could not communicate with ROS master!')
557  sys.exit(2)
558 
559  # This will only retrieve private parameters for this node, but better than nothing
560  params = sorted([p for p in param_list if p.startswith(node_name)])
561 
562  # Fill out a shim node documentation and hack the DocTopicReader to write output
563  doc = NodeInfo()
564  for param in params:
565  param_doc = ParamInfo()
566  param_doc.name = param
567  param_server_array.append(param_doc.name)
568 
569  for param in param_server_array:
570  found = 0
571  for doc in doc_server_array:
572  for doc_param in data.parameters:
573  if doc_param.type == 0:
574  if doc in param:
575  found = 1
576  if doc.find(param) > -1:
577  found = 1
578  if found == 0:
579  unused_param.append(param)
580 
581  print("Set but undocumented params\n")
582  for param in unused_param:
583  print(" " + param)
584 
585  if reverse == True:
586  undocumented_param = []
587  for doc in doc_server_array:
588  found = 0
589  for param in param_server_array:
590  if param.find(doc) > -1:
591  found = 1
592  if found == 0:
593  undocumented_param.append(doc)
594 
595  print("\nDocumented but not set params\n")
596  for param in undocumented_param:
597  print(" " + param)
598 
600  """
601  Entry point for rosman topics command
602  """
603  args = argv[2:]
604  parser = OptionParser(usage='usage: %prog topics topic1 [topic2...]')
605  (options, args) = parser.parse_args(args)
606 
607  rosmaster = rosgraph.Master('/rosman')
608  if not args:
609  parser.error('You must specify at least one topic name')
610  for topic in args:
611  rosman_topic(rosmaster, topic)
612 
614  """
615  Entry point for rosman params command
616  """
617  args = argv[2:]
618  parser = OptionParser(usage='usage: %prog params param1 [param2...]')
619  (options, args) = parser.parse_args(args)
620 
621  rosmaster = rosgraph.Master('/rosman')
622  if not args:
623  parser.error('You must specify at least one param name')
624  for param in args:
625  rosman_param(rosmaster, param)
626 
628  """
629  Entry point for rosman services command
630  """
631  args = argv[2:]
632  parser = OptionParser(usage='usage: %prog services service1 [service2...]')
633  (options, args) = parser.parse_args(args)
634 
635  rosmaster = rosgraph.Master('/rosman')
636  if not args:
637  parser.error('You must specify at least one service name')
638  for serv in args:
639  rosman_service(rosmaster, serv)
640 
641 def _tool_usage(return_error=True):
642  """
643  Print the full usage information for the rosman tool.
644  @param return_error set to true to return from this printout with error code os.EX_USAGE, otherwise exit returning 0.
645  """
646  print("""rosman is a command-line tool for printing documentation about nodes, topics, and parameters from a live or playback system.
647 
648 Commands:
649 \trosman node\tGet overview documentation for a running node
650 \trosman topic\tGet documentation for a desired topic
651 \trosman param\tGet documentation for a desired parameter
652 \trosman service\tGet documentation about a desired service
653 
654 Type rosman <command> -h for more detailed usage, e.g. 'rosman params -h'
655 """)
656  if return_error:
657  sys.exit(getattr(os, 'EX_USAGE', 1))
658  else:
659  sys.exit(0)
660 
661 def rosmanmain(argv=None):
662  """
663  Prints rosman main entrypoint.
664  @param argv: override sys.argv
665  @param argv: [str]
666  """
667  if argv == None:
668  argv = sys.argv
669  if len(argv) == 1:
670  _tool_usage()
671  try:
672  command = argv[1]
673  if command == 'node':
674  _rosman_node_main(argv)
675  elif command == 'check':
676  _rosman_check_main(argv)
677  elif command == 'topic':
678  _rosman_topic_main(argv)
679  elif command == 'param':
680  _rosman_param_main(argv)
681  elif command == 'service':
683  elif command in ('-h', '--help'):
684  _tool_usage(return_error=False)
685  else:
686  _tool_usage()
687  except KeyboardInterrupt:
688  pass
689 
rosman.compare_param
def compare_param(rosmaster, node_name, yaml=False, output_file=sys.stdout, reverse=False)
Definition: __init__.py:508
rosman.DocTopicReader.write_param_info_docstring
def write_param_info_docstring(self, param_info_msg, output_file=sys.stdout)
Definition: __init__.py:159
rosman.DocTopicReader.rosmaster
rosmaster
Definition: __init__.py:36
rosman.DocTopicReader.callback_called
callback_called
Definition: __init__.py:37
rosman.DocTopicReader.read_doc_topic
def read_doc_topic(self, topic, timeout_duration=2.0)
Definition: __init__.py:47
rosman.rosman_node_fallback
def rosman_node_fallback(rosmaster, node_name, yaml=False, output_file=sys.stdout)
Definition: __init__.py:283
rosman.DocTopicReader.write_node_parameters_documentation
def write_node_parameters_documentation(self, output_file, data)
Definition: __init__.py:134
rosman.DocTopicReader.write_service_info_docstring
def write_service_info_docstring(self, service_info_msg, output_file=sys.stdout)
Definition: __init__.py:210
rosman.DocTopicReader.get_doc_msg_param
def get_doc_msg_param(self, input_param)
Definition: __init__.py:222
rosman.rosman_node
def rosman_node(rosmaster, node_name, yaml=False, output_file=sys.stdout)
Definition: __init__.py:272
rosman.get_documentation_publications
def get_documentation_publications(rosmaster, ros_sys_state=None)
Definition: __init__.py:246
rosman.rosman_topic
def rosman_topic(rosmaster, topic)
Definition: __init__.py:377
rosman.DocTopicReader.write_node_header_documentation
def write_node_header_documentation(self, output_file=sys.stdout)
Definition: __init__.py:108
rosman.DocTopicReader.write_node_publishers_documentation
def write_node_publishers_documentation(self, output_file, data)
Definition: __init__.py:126
rosman.rosman_param
def rosman_param(rosmaster, param)
Definition: __init__.py:422
rosman._rosman_check_main
def _rosman_check_main(argv)
Definition: __init__.py:486
rosman.DocTopicReader.get_doc_msg_topic
def get_doc_msg_topic(self, input_topic)
Definition: __init__.py:214
rosman._rosman_topic_main
def _rosman_topic_main(argv)
Definition: __init__.py:599
rosman.DocTopicReader.last_doc_msg
last_doc_msg
Definition: __init__.py:38
rosman.DocTopicReader
Definition: __init__.py:34
rosman._check_master
def _check_master(rosmaster)
Definition: __init__.py:24
rosman.DocTopicReader.write_topic_info_docstring
def write_topic_info_docstring(self, topic_info_msg, output_file=sys.stdout)
Definition: __init__.py:121
rosman._rosman_service_main
def _rosman_service_main(argv)
Definition: __init__.py:627
rosman.DocTopicReader.get_doc_msg_service
def get_doc_msg_service(self, input_service)
Definition: __init__.py:230
rosman.read_documentation_topic
def read_documentation_topic(rosmaster, topic, yaml=False, output_file=sys.stdout)
Definition: __init__.py:238
rosman._tool_usage
def _tool_usage(return_error=True)
Definition: __init__.py:641
rosman._rosman_node_main
def _rosman_node_main(argv)
Definition: __init__.py:459
rosman.rosman_service
def rosman_service(rosmaster, service)
Definition: __init__.py:436
rosman._rosman_param_main
def _rosman_param_main(argv)
Definition: __init__.py:613
rosman.DocTopicReader.write_node_documentation
def write_node_documentation(self, output_file=sys.stdout)
Definition: __init__.py:59
rosman.DocTopicReader.write_node_subscriptions_documentation
def write_node_subscriptions_documentation(self, output_file, data)
Definition: __init__.py:113
rosman._sort_fn
def _sort_fn(e)
Definition: __init__.py:31
rosman.DocTopicReader.write_node_services_documentation
def write_node_services_documentation(self, output_file, data)
Definition: __init__.py:142
rosman.rosmanmain
def rosmanmain(argv=None)
Definition: __init__.py:661
rosman.DocTopicReader.__init__
def __init__(self, rosmaster)
Definition: __init__.py:35
rosman.DocTopicReader.doc_topic_callback
def doc_topic_callback(self, doc_msg)
Definition: __init__.py:43


swri_cli_tools
Author(s): Robert Brothers
autogenerated on Thu Feb 27 2025 03:33:55