11 from itertools
import izip
as zip
15 from optparse
import OptionParser
20 from marti_introspection_msgs.msg
import NodeInfo, TopicInfo, ParamInfo, ServiceInfo
22 DOCUMENTATION_TOPIC_MATCHER = re.compile(
"/documentation$")
29 raise rostopic.ROSTopicIOException(
"Unable to communicate with master!")
41 rospy.init_node(
'rosman', anonymous=
True)
50 timeout = time.time()+timeout_duration
52 not rospy.is_shutdown():
53 rospy.rostime.wallsleep(0.1)
62 print(
'DocTopicReader failed to read documentation topic and cannot write out the node documentation')
76 if item.group
not in groups:
77 groups[item.group] = NodeInfo()
78 groups[item.group].topics.append(item)
81 if item.group
not in groups:
82 groups[item.group] = NodeInfo()
83 groups[item.group].parameters.append(item)
86 if item.group
not in groups:
87 groups[item.group] = NodeInfo()
88 groups[item.group].services.append(item)
100 output_file.write(
"\n\nGroup: {name}\n\n".format(name=group))
109 output_file.write(
"{name} - ({nodelet_manager})\n{description}\n\n".format(name=self.
last_doc_msg.name,
114 output_file.write(
"Subscriptions:\n")
115 subs = [topic
for topic
in data.topics
if topic.advertised ==
False]
117 output_file.write(
' * ')
119 output_file.write(
'\n')
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))
127 output_file.write(
"Publishers:\n")
128 pubs = [topic
for topic
in data.topics
if topic.advertised ==
True]
130 output_file.write(
' * ')
132 output_file.write(
'\n')
136 output_file.write(
"Parameters:\n")
137 for param
in data.parameters:
138 output_file.write(
' * ')
140 output_file.write(
'\n')
143 servs = [service
for service
in data.services
if service.server ==
True]
145 output_file.write(
"Service Servers:\n")
147 output_file.write(
' * ')
149 output_file.write(
'\n')
151 servs = [service
for service
in data.services
if service.server ==
False]
153 output_file.write(
"Service Clients:\n")
155 output_file.write(
' * ')
157 output_file.write(
'\n')
161 type_str =
"unknown_type"
162 if (param_info_msg.type == ParamInfo.TYPE_DOUBLE):
163 default_val = param_info_msg.default_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))
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))
172 elif (param_info_msg.type == ParamInfo.TYPE_STRING):
173 default_val = param_info_msg.default_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))
178 elif (param_info_msg.type == ParamInfo.TYPE_INT):
179 default_val = param_info_msg.default_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))
184 elif (param_info_msg.type == ParamInfo.TYPE_FLOAT):
185 default_val = param_info_msg.default_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))
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))
194 elif (param_info_msg.type == ParamInfo.TYPE_BOOL):
195 default_val =
"true" if param_info_msg.default_bool
else "false"
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))
200 elif (param_info_msg.type == ParamInfo.TYPE_XMLRPC):
202 output_file.write(
"{name} - ({type}) - {description}\n".format(name=param_info_msg.name,
203 type=type_str, description=param_info_msg.description))
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))
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))
218 if doc_topic.resolved_name == input_topic:
226 if doc_param.resolved_name == input_param:
234 if doc_service.resolved_name == input_service:
240 if topic_reader.read_doc_topic(topic):
242 output_file.write(genpy.message.strify_message(topic_reader.last_doc_msg) +
'\n')
244 topic_reader.write_node_documentation(output_file)
248 Get all the current documentation topics in the system
251 if ros_sys_state
is None:
253 ros_sys_state = rosmaster.getSystemState()
255 print(
'Could not communicate with ROS master!')
257 pubs, _, _ = ros_sys_state
259 doc_node_namespaces = []
260 doc_publisher_nodes = []
262 doc_match = DOCUMENTATION_TOPIC_MATCHER.search(t)
265 node_namespace = t[0:doc_match.span()[0]]
267 doc_node_namespaces.append(node_namespace)
268 doc_publisher_nodes.append(n)
270 return doc_topics, doc_node_namespaces, doc_publisher_nodes
272 def rosman_node(rosmaster, node_name, yaml=False, output_file=sys.stdout):
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:
280 node_documentation_found =
True
281 return node_documentation_found
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
292 def topic_type(t, pub_topics):
293 matches = [t_type
for t_name, t_type
in pub_topics
if t_name == t]
296 return 'unknown type'
298 def param_type(param_value):
299 if isinstance(param_value, float):
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
310 return ParamInfo.TYPE_STRING
312 ros_sys_state = rosmaster.getSystemState()
313 pub_topics = rosmaster.getPublishedTopics(
'/')
315 param_list = rosmaster.getParamNames()
317 print(
'Could not communicate with ROS master!')
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])
323 params = sorted([p
for p
in param_list
if p.startswith(node_name)])
328 doc.description =
'Warning: no documentation topic is published for {n}. Falling back to standard rosnode info.'.format(n=node_name)
330 topic_doc = TopicInfo()
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)
337 topic_doc = TopicInfo()
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)
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)
361 if not (srv.endswith(
'get_loggers')
or srv.endswith(
'set_logger_level')):
362 srv_doc = ServiceInfo()
364 srv_doc.resolved_name = srv
366 srv_doc.message_type =
'unknown type'
367 srv_doc.server =
True
368 doc.services.append(srv_doc)
370 topic_reader.last_doc_msg = doc
372 output_file.write(genpy.message.strify_message(doc) +
'\n')
374 topic_reader.write_node_documentation(output_file)
380 ros_sys_state = rosmaster.getSystemState()
382 print(
'Could not communicate with ROS master!')
384 pubs, subs, _ = ros_sys_state
385 topic_documentation_found =
False
386 for t, publisher_nodes
in pubs:
388 for node
in publisher_nodes:
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:
395 if topic_reader.read_doc_topic(doc_topic):
396 topic_doc = topic_reader.get_doc_msg_topic(topic)
398 topic_reader.write_node_header_documentation()
399 topic_reader.write_topic_info_docstring(topic_doc)
400 topic_documentation_found =
True
403 for t, subscriber_nodes
in subs:
405 for node
in subscriber_nodes:
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:
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
419 if topic_documentation_found ==
False:
420 print(
'Could not find published documentation for topic: {t}'.format(t=topic))
423 param_documentation_found =
False
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)
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))
437 service_documentation_found =
False
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
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))
461 Entry point for rosman node command
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)
472 parser.error(
'You must specify at least one node name')
474 ros_master = rosgraph.Master(
'/rosman')
476 with open(options.filename,
'a')
as output_file:
478 if not rosman_node(ros_master, node, yaml=options.yaml, output_file=output_file):
483 if not rosman_node(ros_master, node, yaml=options.yaml):
488 Entry point for rosman check command
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)
500 parser.error(
'You must specify at least one node name')
502 ros_master = rosgraph.Master(
'/rosman')
506 compare_param(ros_master, node, yaml=options.yaml, reverse=options.reverse)
508 def compare_param(rosmaster, node_name, yaml=False, output_file=sys.stdout, reverse=False):
509 doc_server_array = []
510 param_server_array = []
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:
518 if topic_reader.read_doc_topic(topic):
520 if (topic_reader.last_doc_msg
is None):
521 print(
'DocTopicReader failed to read documentation topic and cannot write out the node documentation')
524 topic_reader.last_doc_msg.parameters.sort(key=_sort_fn)
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)
534 if len(topic_reader.last_doc_msg.parameters) > 0:
536 for param
in data.parameters:
538 doc_server_array.append(param.resolved_name)
544 if len(topic_reader.last_doc_msg.parameters) > 0:
545 for param
in data.parameters:
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")
553 ros_sys_state = rosmaster.getSystemState()
554 param_list = rosmaster.getParamNames()
556 print(
'Could not communicate with ROS master!')
560 params = sorted([p
for p
in param_list
if p.startswith(node_name)])
565 param_doc = ParamInfo()
566 param_doc.name = param
567 param_server_array.append(param_doc.name)
569 for param
in param_server_array:
571 for doc
in doc_server_array:
572 for doc_param
in data.parameters:
573 if doc_param.type == 0:
576 if doc.find(param) > -1:
579 unused_param.append(param)
581 print(
"Set but undocumented params\n")
582 for param
in unused_param:
586 undocumented_param = []
587 for doc
in doc_server_array:
589 for param
in param_server_array:
590 if param.find(doc) > -1:
593 undocumented_param.append(doc)
595 print(
"\nDocumented but not set params\n")
596 for param
in undocumented_param:
601 Entry point for rosman topics command
604 parser = OptionParser(usage=
'usage: %prog topics topic1 [topic2...]')
605 (options, args) = parser.parse_args(args)
607 rosmaster = rosgraph.Master(
'/rosman')
609 parser.error(
'You must specify at least one topic name')
615 Entry point for rosman params command
618 parser = OptionParser(usage=
'usage: %prog params param1 [param2...]')
619 (options, args) = parser.parse_args(args)
621 rosmaster = rosgraph.Master(
'/rosman')
623 parser.error(
'You must specify at least one param name')
629 Entry point for rosman services command
632 parser = OptionParser(usage=
'usage: %prog services service1 [service2...]')
633 (options, args) = parser.parse_args(args)
635 rosmaster = rosgraph.Master(
'/rosman')
637 parser.error(
'You must specify at least one service name')
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.
646 print(
"""rosman is a command-line tool for printing documentation about nodes, topics, and parameters from a live or playback system.
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
654 Type rosman <command> -h for more detailed usage, e.g. 'rosman params -h'
657 sys.exit(getattr(os,
'EX_USAGE', 1))
663 Prints rosman main entrypoint.
664 @param argv: override sys.argv
673 if command ==
'node':
675 elif command ==
'check':
677 elif command ==
'topic':
679 elif command ==
'param':
681 elif command ==
'service':
683 elif command
in (
'-h',
'--help'):
687 except KeyboardInterrupt: