1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37 from __future__ import division, print_function
38
39 NAME='rostopic'
40
41 import os
42 import sys
43 import math
44 import socket
45 import time
46 import traceback
47 import yaml
48 import xmlrpclib
49
50 from operator import itemgetter
51 from urlparse import urlparse
52
53 import genpy
54
55 import roslib.message
56 import rosgraph
57
58 import rospy
59
61 """
62 Base exception class of rostopic-related errors
63 """
64 pass
66 """
67 rostopic errors related to network I/O failures
68 """
69 pass
70
72 """
73 Make sure that master is available
74 :raises: :exc:`ROSTopicException` If unable to successfully communicate with master
75 """
76 try:
77 rosgraph.Master('/rostopic').getPid()
78 except socket.error:
79 raise ROSTopicIOException("Unable to communicate with master!")
80
82 try:
83 val = master.getTopicTypes()
84 except xmlrpclib.Fault:
85
86 sys.stderr.write("WARNING: rostopic is being used against an older version of ROS/roscore\n")
87 val = master.getPublishedTopics('/')
88 return val
89
91 """
92 ROSTopicHz receives messages for a topic and computes frequency stats
93 """
94 - def __init__(self, window_size, filter_expr=None):
95 import threading
96 self.lock = threading.Lock()
97 self.last_printed_tn = 0
98 self.msg_t0 = -1.
99 self.msg_tn = 0
100 self.times =[]
101 self.filter_expr = filter_expr
102
103
104 if window_size < 0:
105 window_size = 50000
106 self.window_size = window_size
107
109 """
110 ros sub callback
111 :param m: Message instance
112 """
113
114 if self.filter_expr is not None and not self.filter_expr(m):
115 return
116 with self.lock:
117 curr_rostime = rospy.get_rostime()
118
119
120 if curr_rostime.is_zero():
121 if len(self.times) > 0:
122 print("time has reset, resetting counters")
123 self.times = []
124 return
125
126 curr = curr_rostime.to_sec()
127 if self.msg_t0 < 0 or self.msg_t0 > curr:
128 self.msg_t0 = curr
129 self.msg_tn = curr
130 self.times = []
131 else:
132 self.times.append(curr - self.msg_tn)
133 self.msg_tn = curr
134
135
136 if len(self.times) > self.window_size - 1:
137 self.times.pop(0)
138
140 """
141 print the average publishing rate to screen
142 """
143 if not self.times:
144 return
145 elif self.msg_tn == self.last_printed_tn:
146 print("no new messages")
147 return
148 with self.lock:
149
150
151
152
153
154
155
156
157
158 n = len(self.times)
159
160 mean = sum(self.times) / n
161 rate = 1./mean if mean > 0. else 0
162
163
164 std_dev = math.sqrt(sum((x - mean)**2 for x in self.times) /n)
165
166
167 max_delta = max(self.times)
168 min_delta = min(self.times)
169
170 self.last_printed_tn = self.msg_tn
171 print("average rate: %.3f\n\tmin: %.3fs max: %.3fs std dev: %.5fs window: %s"%(rate, min_delta, max_delta, std_dev, n+1))
172
174 rospy.rostime.wallsleep(duration)
175
177 """
178 Periodically print the publishing rate of a topic to console until
179 shutdown
180 :param topic: topic name, ``str``
181 :param window_size: number of messages to average over, -1 for infinite, ``int``
182 :param filter_expr: Python filter expression that is called with m, the message instance
183 """
184 msg_class, real_topic, _ = get_topic_class(topic, blocking=True)
185 if rospy.is_shutdown():
186 return
187 rospy.init_node(NAME, anonymous=True)
188 rt = ROSTopicHz(window_size, filter_expr=filter_expr)
189
190
191 if filter_expr is not None:
192
193 sub = rospy.Subscriber(real_topic, msg_class, rt.callback_hz)
194 else:
195 sub = rospy.Subscriber(real_topic, rospy.AnyMsg, rt.callback_hz)
196 print("subscribed to [%s]"%real_topic)
197 while not rospy.is_shutdown():
198 _sleep(1.0)
199 rt.print_hz()
200
203 import threading
204 self.lock = threading.Lock()
205 self.last_printed_tn = 0
206 self.sizes =[]
207 self.times =[]
208 self.window_size = window_size or 100
209
211 """ros sub callback"""
212 with self.lock:
213 try:
214 t = time.time()
215 self.times.append(t)
216 self.sizes.append(len(data._buff))
217 assert(len(self.times) == len(self.sizes))
218
219 if len(self.times) > self.window_size:
220 self.times.pop(0)
221 self.sizes.pop(0)
222 except:
223 traceback.print_exc()
224
226 """print the average publishing rate to screen"""
227 if len(self.times) < 2:
228 return
229 with self.lock:
230 n = len(self.times)
231 tn = time.time()
232 t0 = self.times[0]
233
234 total = sum(self.sizes)
235 bytes_per_s = total / (tn - t0)
236 mean = total / n
237
238
239
240
241 max_s = max(self.sizes)
242 min_s = min(self.sizes)
243
244
245 if bytes_per_s < 1000:
246 bw, mean, min_s, max_s = ["%.2fB"%v for v in [bytes_per_s, mean, min_s, max_s]]
247 elif bytes_per_s < 1000000:
248 bw, mean, min_s, max_s = ["%.2fKB"%(v/1000) for v in [bytes_per_s, mean, min_s, max_s]]
249 else:
250 bw, mean, min_s, max_s = ["%.2fMB"%(v/1000000) for v in [bytes_per_s, mean, min_s, max_s]]
251
252 print("average: %s/s\n\tmean: %s min: %s max: %s window: %s"%(bw, mean, min_s, max_s, n))
253
255 """
256 periodically print the received bandwidth of a topic to console until
257 shutdown
258 """
259 _check_master()
260 _, real_topic, _ = get_topic_type(topic, blocking=True)
261 if rospy.is_shutdown():
262 return
263
264 rospy.init_node(NAME, anonymous=True, disable_rostime=True)
265 rt = ROSTopicBandwidth(window_size)
266
267
268 sub = rospy.Subscriber(real_topic, rospy.AnyMsg, rt.callback)
269 print("subscribed to [%s]"%real_topic)
270 while not rospy.is_shutdown():
271 _sleep(1.0)
272 rt.print_bw()
273
274
275
277 """
278 Generates a function that returns the relevant field (aka 'subtopic') of a Message object
279 :param pattern: subtopic, e.g. /x. Must have a leading '/' if specified, ``str``
280 :returns: function that converts a message into the desired value, ``fn(Message) -> value``
281 """
282 if not pattern or pattern == '/':
283 return None
284 def msgeval(msg):
285
286 try:
287 return eval('msg'+'.'.join(pattern.split('/')))
288 except AttributeError as e:
289 sys.stdout.write("no field named [%s]"%pattern+"\n")
290 return None
291 return msgeval
292
294 """
295 subroutine for getting the topic type
296 :returns: topic type, real topic name and fn to evaluate the message instance
297 if the topic points to a field within a topic, e.g. /rosout/msg, ``(str, str, fn)``
298 """
299 try:
300 val = _master_get_topic_types(rosgraph.Master('/rostopic'))
301 except socket.error:
302 raise ROSTopicIOException("Unable to communicate with master!")
303
304
305 matches = [(t, t_type) for t, t_type in val if t == topic]
306 if not matches:
307 matches = [(t, t_type) for t, t_type in val if topic.startswith(t+'/')]
308
309 matches.sort(key=itemgetter(0), reverse=True)
310 if matches:
311 t, t_type = matches[0]
312 if t_type == rosgraph.names.ANYTYPE:
313 return None, None, None
314 return t_type, t, msgevalgen(topic[len(t):])
315 else:
316 return None, None, None
317
318
319
321 """
322 Get the topic type.
323
324 :param topic: topic name, ``str``
325 :param blocking: (default False) block until topic becomes available, ``bool``
326
327 :returns: topic type, real topic name and fn to evaluate the message instance
328 if the topic points to a field within a topic, e.g. /rosout/msg. fn is None otherwise. ``(str, str, fn)``
329 :raises: :exc:`ROSTopicException` If master cannot be contacted
330 """
331 topic_type, real_topic, msg_eval = _get_topic_type(topic)
332 if topic_type:
333 return topic_type, real_topic, msg_eval
334 elif blocking:
335 sys.stderr.write("WARNING: topic [%s] does not appear to be published yet\n"%topic)
336 while not rospy.is_shutdown():
337 topic_type, real_topic, msg_eval = _get_topic_type(topic)
338 if topic_type:
339 return topic_type, real_topic, msg_eval
340 else:
341 _sleep(0.1)
342 return None, None, None
343
345 """
346 Get the topic message class
347 :returns: message class for topic, real topic
348 name, and function for evaluating message objects into the subtopic
349 (or ``None``). ``(Message, str, str)``
350 :raises: :exc:`ROSTopicException` If topic type cannot be determined or loaded
351 """
352 topic_type, real_topic, msg_eval = get_topic_type(topic, blocking=blocking)
353 if topic_type is None:
354 return None, None, None
355 msg_class = roslib.message.get_message_class(topic_type)
356 if not msg_class:
357 raise ROSTopicException("Cannot load message class for [%s]. Are your messages built?"%topic_type)
358 return msg_class, real_topic, msg_eval
359
361 """
362 get CSV representation of fields used by _str_plot
363 :returns: list of fields as a CSV string, ``str``
364 """
365 s = _sub_str_plot_fields(val, f, field_filter)
366 if s is not None:
367 return "time,"+s
368 else:
369 return 'time,'
370
372 """recursive helper function for _str_plot_fields"""
373
374 type_ = type(val)
375 if type_ in (bool, int, float) or \
376 isinstance(val, genpy.TVal):
377 return f
378
379 elif hasattr(val, "_slot_types"):
380 if field_filter is not None:
381 fields = list(field_filter(val))
382 else:
383 fields = val.__slots__
384 sub = (_sub_str_plot_fields(_convert_getattr(val, a, t), f+"."+a, field_filter) for a,t in zip(val.__slots__, val._slot_types) if a in fields)
385 sub = [s for s in sub if s is not None]
386 if sub:
387 return ','.join([s for s in sub])
388 elif type_ in (str, unicode):
389 return f
390 elif type_ in (list, tuple):
391 if len(val) == 0:
392 return None
393 val0 = val[0]
394 type0 = type(val0)
395
396 if type0 in (bool, int, float) or \
397 isinstance(val0, genpy.TVal):
398 return ','.join(["%s%s"%(f,x) for x in xrange(0,len(val))])
399 elif type0 in (str, unicode):
400
401 return ','.join(["%s%s"%(f,x) for x in xrange(0,len(val))])
402 elif hasattr(val0, "_slot_types"):
403 labels = ["%s%s"%(f,x) for x in xrange(0,len(val))]
404 sub = [s for s in [_sub_str_plot_fields(v, sf, field_filter) for v,sf in zip(val, labels)] if s]
405 if sub:
406 return ','.join([s for s in sub])
407 return None
408
409
410 -def _str_plot(val, time_offset=None, current_time=None, field_filter=None, type_information=None):
411 """
412 Convert value to matlab/octave-friendly CSV string representation.
413
414 :param val: message
415 :param current_time: current :class:`genpy.Time` to use if message does not contain its own timestamp.
416 :param time_offset: (optional) for time printed for message, print as offset against this :class:`genpy.Time`
417 :param field_filter: filter the fields that are strified for Messages, ``fn(Message)->iter(str)``
418 :returns: comma-separated list of field values in val, ``str``
419 """
420
421 s = _sub_str_plot(val, time_offset, field_filter)
422 if s is None:
423 s = ''
424
425 if time_offset is not None:
426 time_offset = time_offset.to_nsec()
427 else:
428 time_offset = 0
429
430 if current_time is not None:
431 return "%s,%s"%(current_time.to_nsec()-time_offset, s)
432 elif getattr(val, "_has_header", False):
433 return "%s,%s"%(val.header.stamp.to_nsec()-time_offset, s)
434 else:
435 return "%s,%s"%(rospy.get_rostime().to_nsec()-time_offset, s)
436
438 """Helper routine for _str_plot."""
439
440 type_ = type(val)
441
442 if type_ == bool:
443 return '1' if val else '0'
444 elif type_ in (int, float) or \
445 isinstance(val, genpy.TVal):
446 if time_offset is not None and isinstance(val, genpy.Time):
447 return str(val-time_offset)
448 else:
449 return str(val)
450 elif hasattr(val, "_slot_types"):
451 if field_filter is not None:
452 fields = list(field_filter(val))
453 else:
454 fields = val.__slots__
455
456 sub = (_sub_str_plot(_convert_getattr(val, f, t), time_offset, field_filter) for f,t in zip(val.__slots__, val._slot_types) if f in fields)
457 sub = [s for s in sub if s is not None]
458 if sub:
459 return ','.join(sub)
460 elif type_ in (str, unicode):
461 return val
462 elif type_ in (list, tuple):
463 if len(val) == 0:
464 return None
465 val0 = val[0]
466
467 type0 = type(val0)
468 if type0 == bool:
469 return ','.join([('1' if v else '0') for v in val])
470 elif type0 in (int, float) or \
471 isinstance(val0, genpy.TVal):
472 return ','.join([str(v) for v in val])
473 elif type0 in (str, unicode):
474 return ','.join([v for v in val])
475 elif hasattr(val0, "_slot_types"):
476 sub = [s for s in [_sub_str_plot(v, time_offset, field_filter) for v in val] if s is not None]
477 if sub:
478 return ','.join([s for s in sub])
479 return None
480
481
483 """
484 Convert atttribute types on the fly, if necessary. This is mainly
485 to convert uint8[] fields back to an array type.
486 """
487 attr = getattr(val, f)
488 if type(attr) in (str, unicode) and 'uint8[' in t:
489 return [ord(x) for x in attr]
490 else:
491 return attr
492
494 """
495 Callback instance that can print callback data in a variety of
496 formats. Used for all variants of rostopic echo
497 """
498
499 - def __init__(self, topic, msg_eval, plot=False, filter_fn=None,
500 echo_clear=False, echo_all_topics=False,
501 offset_time=False, count=None,
502 field_filter_fn=None):
503 """
504 :param plot: if ``True``, echo in plotting-friendly format, ``bool``
505 :param filter_fn: function that evaluates to ``True`` if message is to be echo'd, ``fn(topic, msg)``
506 :param echo_all_topics: (optional) if ``True``, echo all messages in bag, ``bool``
507 :param offset_time: (optional) if ``True``, display time as offset from current time, ``bool``
508 :param count: number of messages to echo, ``None`` for infinite, ``int``
509 :param field_filter_fn: filter the fields that are strified for Messages, ``fn(Message)->iter(str)``
510 """
511 if topic and topic[-1] == '/':
512 topic = topic[:-1]
513 self.topic = topic
514 self.msg_eval = msg_eval
515 self.plot = plot
516 self.filter_fn = filter_fn
517
518 self.prefix = ''
519 self.suffix = '\n---' if not plot else ''
520
521 self.echo_all_topics = echo_all_topics
522 self.offset_time = offset_time
523
524
525 self.done = False
526 self.max_count = count
527 self.count = 0
528
529
530 if plot:
531
532 self.str_fn = _str_plot
533 self.sep = ''
534 else:
535
536 self.str_fn = self.custom_strify_message
537 if echo_clear:
538 self.prefix = '\033[2J\033[;H'
539
540 self.field_filter=field_filter_fn
541
542
543 self.first = True
544
545
546 self.last_topic = None
547 self.last_msg_eval = None
548
549 - def custom_strify_message(self, val, indent='', time_offset=None, current_time=None, field_filter=None, type_information=None):
550
551 if type_information and type_information.startswith('uint8['):
552 val = [ord(x) for x in val]
553 return genpy.message.strify_message(val, indent=indent, time_offset=time_offset, current_time=current_time, field_filter=field_filter)
554
555 - def callback(self, data, callback_args, current_time=None):
556 """
557 Callback to pass to rospy.Subscriber or to call
558 manually. rospy.Subscriber constructor must also pass in the
559 topic name as an additional arg
560 :param data: Message
561 :param topic: topic name, ``str``
562 :param current_time: override calculation of current time, :class:`genpy.Time`
563 """
564 topic = callback_args['topic']
565 type_information = callback_args.get('type_information', None)
566 if self.filter_fn is not None and not self.filter_fn(data):
567 return
568
569 if self.max_count is not None and self.count >= self.max_count:
570 self.done = True
571 return
572
573 try:
574 msg_eval = self.msg_eval
575 if topic == self.topic:
576 pass
577 elif self.topic.startswith(topic + '/'):
578
579 if topic == self.last_topic:
580
581 msg_eval = self.last_msg_eval
582 else:
583
584 self.last_msg_eval = msg_eval = msgevalgen(self.topic[len(topic):])
585 self.last_topic = topic
586 elif not self.echo_all_topics:
587 return
588
589 if msg_eval is not None:
590 data = msg_eval(data)
591
592
593 if data is not None:
594
595
596 self.count += 1
597
598
599 if self.plot and self.first:
600 sys.stdout.write("%"+_str_plot_fields(data, 'field', self.field_filter)+'\n')
601 self.first = False
602
603 if self.offset_time:
604 sys.stdout.write(self.prefix+\
605 self.str_fn(data, time_offset=rospy.get_rostime(),
606 current_time=current_time, field_filter=self.field_filter, type_information=type_information) + \
607 self.suffix + '\n')
608 else:
609 sys.stdout.write(self.prefix+\
610 self.str_fn(data,
611 current_time=current_time, field_filter=self.field_filter, type_information=type_information) + \
612 self.suffix + '\n')
613
614
615 sys.stdout.flush()
616
617 if self.max_count is not None and self.count >= self.max_count:
618 self.done = True
619
620 except IOError:
621 self.done = True
622 except:
623
624 self.done = True
625 traceback.print_exc()
626
628 """
629 Print ROS message type of topic to screen
630 :param topic: topic name, ``str``
631 """
632 t, _, _ = get_topic_type(topic, blocking=False)
633 if t:
634 print(t)
635 else:
636 sys.stderr.write('unknown topic type [%s]\n'%topic)
637 sys.exit(1)
638
640 """
641 :param callback_echo: :class:`CallbackEcho` instance to invoke on new messages in bag file
642 :param bag_file: name of bag file to echo messages from or ``None``, ``str``
643 """
644 if not os.path.exists(bag_file):
645 raise ROSTopicException("bag file [%s] does not exist"%bag_file)
646 first = True
647
648 import rosbag
649 with rosbag.Bag(bag_file) as b:
650 for t, msg, timestamp in b.read_messages():
651
652
653 if t[0] != '/':
654 t = rosgraph.names.script_resolve_name('rostopic', t)
655 callback_echo.callback(msg, {'topic': t}, current_time=timestamp)
656
657 if callback_echo.done:
658 break
659
660 -def _rostopic_echo(topic, callback_echo, bag_file=None, echo_all_topics=False):
661 """
662 Print new messages on topic to screen.
663
664 :param topic: topic name, ``str``
665 :param bag_file: name of bag file to echo messages from or ``None``, ``str``
666 """
667
668
669 if bag_file:
670
671 rospy.rostime.set_rostime_initialized(True)
672 _rostopic_echo_bag(callback_echo, bag_file)
673 else:
674 _check_master()
675 rospy.init_node(NAME, anonymous=True)
676 msg_class, real_topic, msg_eval = get_topic_class(topic, blocking=True)
677 if msg_class is None:
678
679 return
680 callback_echo.msg_eval = msg_eval
681
682
683 type_information = None
684 if len(topic) > len(real_topic):
685 subtopic = topic[len(real_topic):]
686 subtopic = subtopic.strip('/')
687 if subtopic:
688 fields = subtopic.split('/')
689 submsg_class = msg_class
690 while fields:
691 field = fields[0].split('[')[0]
692 del fields[0]
693 index = submsg_class.__slots__.index(field)
694 type_information = submsg_class._slot_types[index]
695 if fields:
696 submsg_class = roslib.message.get_message_class(type_information)
697
698 use_sim_time = rospy.get_param('/use_sim_time', False)
699 sub = rospy.Subscriber(real_topic, msg_class, callback_echo.callback, {'topic': topic, 'type_information': type_information})
700
701 if use_sim_time:
702
703
704 timeout_t = time.time() + 2.
705 while time.time() < timeout_t and \
706 callback_echo.count == 0 and \
707 not rospy.is_shutdown() and \
708 not callback_echo.done:
709 _sleep(0.1)
710
711 if callback_echo.count == 0 and \
712 not rospy.is_shutdown() and \
713 not callback_echo.done:
714 sys.stderr.write("WARNING: no messages received and simulated time is active.\nIs /clock being published?\n")
715
716 while not rospy.is_shutdown() and not callback_echo.done:
717 _sleep(0.1)
718
719 _caller_apis = {}
721 """
722 Get XML-RPC API of node
723 :param master: XML-RPC handle to ROS Master, :class:`xmlrpclib.ServerProxy`
724 :param caller_id: node name, ``str``
725 :returns: XML-RPC URI of node, ``str``
726 :raises: :exc:`ROSTopicIOException` If unable to communicate with master
727 """
728 caller_api = _caller_apis.get(caller_id, None)
729 if not caller_api:
730 try:
731 caller_api = master.lookupNode(caller_id)
732 _caller_apis[caller_id] = caller_api
733 except socket.error:
734 raise ROSTopicIOException("Unable to communicate with master!")
735 except rosgraph.MasterError:
736 caller_api = 'unknown address %s'%caller_id
737
738 return caller_api
739
741 """
742 Prints topics in bag file to screen
743 :param bag_file: path to bag file, ``str``
744 :param topic: optional topic name to match. Will print additional information just about messagese in this topic, ``str``
745 """
746 import rosbag
747 if not os.path.exists(bag_file):
748 raise ROSTopicException("bag file [%s] does not exist"%bag_file)
749
750 with rosbag.Bag(bag_file) as b:
751 if topic:
752
753 topic_ns = rosgraph.names.make_global_ns(topic)
754 count = 0
755 earliest = None
756 latest = None
757 for top, msg, t in b.read_messages(raw=True):
758 if top == topic or top.startswith(topic_ns):
759 count += 1
760 if earliest == None:
761 earliest = t
762
763 latest = t
764 if rospy.is_shutdown():
765 break
766 import time
767 earliest, latest = [time.strftime("%d %b %Y %H:%M:%S", time.localtime(t.to_time())) for t in (earliest, latest)]
768 print("%s message(s) from %s to %s"%(count, earliest, latest))
769 else:
770 topics = set()
771 for top, msg, _ in b.read_messages(raw=True):
772 if top not in topics:
773 print(top)
774 topics.add(top)
775 if rospy.is_shutdown():
776 break
777
778 -def _sub_rostopic_list(master, pubs, subs, publishers_only, subscribers_only, verbose, indent=''):
779 def topic_type(t, topic_types):
780 matches = [t_type for t_name, t_type in topic_types if t_name == t]
781 if matches:
782 return matches[0]
783 return 'unknown type'
784
785 if verbose:
786 topic_types = _master_get_topic_types(master)
787
788 if not subscribers_only:
789 print("\n%sPublished topics:"%indent)
790 for t, l in pubs:
791 if len(l) > 1:
792 print(indent+" * %s [%s] %s publishers"%(t, topic_type(t, topic_types), len(l)))
793 else:
794 print(indent+" * %s [%s] 1 publisher"%(t, topic_type(t, topic_types)))
795
796 if not publishers_only:
797 print(indent)
798 print(indent+"Subscribed topics:")
799 for t,l in subs:
800 if len(l) > 1:
801 print(indent+" * %s [%s] %s subscribers"%(t, topic_type(t, topic_types), len(l)))
802 else:
803 print(indent+" * %s [%s] 1 subscriber"%(t, topic_type(t, topic_types)))
804 print('')
805 else:
806 if publishers_only:
807 topics = [t for t,_ in pubs]
808 elif subscribers_only:
809 topics = [t for t,_ in subs]
810 else:
811 topics = list(set([t for t,_ in pubs] + [t for t,_ in subs]))
812 topics.sort()
813 print('\n'.join(["%s%s"%(indent, t) for t in topics]))
814
815
817 """
818 Build up maps for hostname to topic list per hostname
819 :returns: publishers host map, subscribers host map, ``{str: set(str)}, {str: set(str)}``
820 """
821 def build_map(master, state, uricache):
822 tmap = {}
823 for topic, tnodes in state:
824 for p in tnodes:
825 if not p in uricache:
826 uricache[p] = master.lookupNode(p)
827 uri = uricache[p]
828 puri = urlparse(uri)
829 if not puri.hostname in tmap:
830 tmap[puri.hostname] = []
831
832 matches = [l for x, l in tmap[puri.hostname] if x == topic]
833 if matches:
834 matches[0].append(p)
835 else:
836 tmap[puri.hostname].append((topic, [p]))
837 return tmap
838
839 uricache = {}
840 host_pub_topics = build_map(master, pubs, uricache)
841 host_sub_topics = build_map(master, subs, uricache)
842 return host_pub_topics, host_sub_topics
843
844 -def _rostopic_list(topic, verbose=False,
845 subscribers_only=False, publishers_only=False,
846 group_by_host=False):
847 """
848 Print topics to screen
849
850 :param topic: topic name to list information or None to match all topics, ``str``
851 :param verbose: print additional debugging information, ``bool``
852 :param subscribers_only: print information about subscriptions only, ``bool``
853 :param publishers_only: print information about subscriptions only, ``bool``
854 :param group_by_host: group topic list by hostname, ``bool``
855 """
856
857 if subscribers_only and publishers_only:
858 raise ROSTopicException("cannot specify both subscribers- and publishers-only")
859
860 master = rosgraph.Master('/rostopic')
861 try:
862 state = master.getSystemState()
863
864 pubs, subs, _ = state
865 if topic:
866
867 topic_ns = rosgraph.names.make_global_ns(topic)
868 subs = (x for x in subs if x[0] == topic or x[0].startswith(topic_ns))
869 pubs = (x for x in pubs if x[0] == topic or x[0].startswith(topic_ns))
870
871 except socket.error:
872 raise ROSTopicIOException("Unable to communicate with master!")
873
874 if group_by_host:
875
876 host_pub_topics, host_sub_topics = _rostopic_list_group_by_host(master, pubs, subs)
877 for hostname in set(list(host_pub_topics.keys()) + list(host_sub_topics.keys())):
878 pubs, subs = host_pub_topics.get(hostname,[]), host_sub_topics.get(hostname, []),
879 if (pubs and not subscribers_only) or (subs and not publishers_only):
880 print("Host [%s]:" % hostname)
881 _sub_rostopic_list(master, pubs, subs,
882 publishers_only, subscribers_only,
883 verbose, indent=' ')
884 else:
885 _sub_rostopic_list(master, pubs, subs,
886 publishers_only, subscribers_only,
887 verbose)
888
889 -def get_info_text(topic):
890 """
891 Get human-readable topic description
892
893 :param topic: topic name, ``str``
894 """
895 import cStringIO, itertools
896 buff = cStringIO.StringIO()
897 def topic_type(t, topic_types):
898 matches = [t_type for t_name, t_type in topic_types if t_name == t]
899 if matches:
900 return matches[0]
901 return 'unknown type'
902
903 master = rosgraph.Master('/rostopic')
904 try:
905 state = master.getSystemState()
906
907 pubs, subs, _ = state
908
909 subs = [x for x in subs if x[0] == topic]
910 pubs = [x for x in pubs if x[0] == topic]
911
912 topic_types = _master_get_topic_types(master)
913
914 except socket.error:
915 raise ROSTopicIOException("Unable to communicate with master!")
916
917 if not pubs and not subs:
918 raise ROSTopicException("Unknown topic %s"%topic)
919
920 buff.write("Type: %s\n\n"%topic_type(topic, topic_types))
921
922 if pubs:
923 buff.write("Publishers: \n")
924 for p in itertools.chain(*[l for x, l in pubs]):
925 buff.write(" * %s (%s)\n"%(p, get_api(master, p)))
926 else:
927 buff.write("Publishers: None\n")
928 buff.write('\n')
929
930 if subs:
931 buff.write("Subscribers: \n")
932 for p in itertools.chain(*[l for x, l in subs]):
933 buff.write(" * %s (%s)\n"%(p, get_api(master, p)))
934 else:
935 buff.write("Subscribers: None\n")
936 buff.write('\n')
937 return buff.getvalue()
938
940 """
941 Print topic information to screen.
942
943 :param topic: topic name, ``str``
944 """
945 print(get_info_text(topic))
946
947
948
949
951 def expr_eval(expr):
952 def eval_fn(m):
953 return eval(expr)
954 return eval_fn
955
956 args = argv[2:]
957 from optparse import OptionParser
958 parser = OptionParser(usage="usage: %prog echo [options] /topic", prog=NAME)
959 parser.add_option("-b", "--bag",
960 dest="bag", default=None,
961 help="echo messages from .bag file", metavar="BAGFILE")
962 parser.add_option("-p",
963 dest="plot", default=False,
964 action="store_true",
965 help="echo in a plotting friendly format")
966 parser.add_option("--filter",
967 dest="filter_expr", default=None,
968 metavar="FILTER-EXPRESSION",
969 help="Python expression to filter messages that are printed. Expression can use Python builtins as well as m (the message) and topic (the topic name).")
970 parser.add_option("--nostr",
971 dest="nostr", default=False,
972 action="store_true",
973 help="exclude string fields")
974 parser.add_option("--noarr",
975 dest="noarr", default=False,
976 action="store_true",
977 help="exclude arrays")
978 parser.add_option("-c", "--clear",
979 dest="clear", default=False,
980 action="store_true",
981 help="clear screen before printing next message")
982 parser.add_option("-a", "--all",
983 dest="all_topics", default=False,
984 action="store_true",
985 help="display all message in bag, only valid with -b option")
986 parser.add_option("-n",
987 dest="msg_count", default=None, metavar="COUNT",
988 help="number of messages to echo")
989 parser.add_option("--offset",
990 dest="offset_time", default=False,
991 action="store_true",
992 help="display time as offsets from current time (in seconds)")
993
994 (options, args) = parser.parse_args(args)
995 if len(args) > 1:
996 parser.error("you may only specify one input topic")
997 if options.all_topics and not options.bag:
998 parser.error("Display all option is only valid when echoing from bag files")
999 if options.offset_time and options.bag:
1000 parser.error("offset time option is not valid with bag files")
1001 if options.all_topics:
1002 topic = ''
1003 else:
1004 if len(args) == 0:
1005 parser.error("topic must be specified")
1006 topic = rosgraph.names.script_resolve_name('rostopic', args[0])
1007
1008
1009
1010
1011 filter_fn = None
1012 if options.filter_expr:
1013 filter_fn = expr_eval(options.filter_expr)
1014
1015 try:
1016 msg_count = int(options.msg_count) if options.msg_count else None
1017 except ValueError:
1018 parser.error("COUNT must be an integer")
1019
1020 field_filter_fn = create_field_filter(options.nostr, options.noarr)
1021 callback_echo = CallbackEcho(topic, None, plot=options.plot,
1022 filter_fn=filter_fn,
1023 echo_clear=options.clear, echo_all_topics=options.all_topics,
1024 offset_time=options.offset_time, count=msg_count,
1025 field_filter_fn=field_filter_fn)
1026 try:
1027 _rostopic_echo(topic, callback_echo, bag_file=options.bag)
1028 except socket.error:
1029 sys.stderr.write("Network communication failed. Most likely failed to communicate with master.\n")
1030
1032 def field_filter(val):
1033 fields = val.__slots__
1034 field_types = val._slot_types
1035 for f, t in zip(val.__slots__, val._slot_types):
1036 if echo_noarr and '[' in t:
1037 continue
1038 elif echo_nostr and 'string' in t:
1039 continue
1040 yield f
1041 return field_filter
1042
1044 args = argv[2:]
1045 from optparse import OptionParser
1046 parser = OptionParser(usage="usage: %%prog %s /topic"%cmd, prog=NAME)
1047 (options, args) = parser.parse_args(args)
1048 if len(args) == 0:
1049 parser.error("topic must be specified")
1050 if len(args) > 1:
1051 parser.error("you may only specify one input topic")
1052 return rosgraph.names.script_resolve_name('rostopic', args[0])
1053
1055 _rostopic_type(_optparse_topic_only('type', argv))
1056
1058 args = argv[2:]
1059 from optparse import OptionParser
1060 parser = OptionParser(usage="usage: %prog hz /topic", prog=NAME)
1061 parser.add_option("-w", "--window",
1062 dest="window_size", default=-1,
1063 help="window size, in # of messages, for calculating rate", metavar="WINDOW")
1064 parser.add_option("--filter",
1065 dest="filter_expr", default=None,
1066 help="only measure messages matching the specified Python expression", metavar="EXPR")
1067
1068 (options, args) = parser.parse_args(args)
1069 if len(args) == 0:
1070 parser.error("topic must be specified")
1071 if len(args) > 1:
1072 parser.error("you may only specify one input topic")
1073 try:
1074 if options.window_size != -1:
1075 import string
1076 window_size = string.atoi(options.window_size)
1077 else:
1078 window_size = options.window_size
1079 except:
1080 parser.error("window size must be an integer")
1081 topic = rosgraph.names.script_resolve_name('rostopic', args[0])
1082
1083
1084 if options.filter_expr:
1085 def expr_eval(expr):
1086 def eval_fn(m):
1087 return eval(expr)
1088 return eval_fn
1089 filter_expr = expr_eval(options.filter_expr)
1090 else:
1091 filter_expr = None
1092 _rostopic_hz(topic, window_size=window_size, filter_expr=filter_expr)
1093
1095 args = argv[2:]
1096 from optparse import OptionParser
1097 parser = OptionParser(usage="usage: %prog bw /topic", prog=NAME)
1098 parser.add_option("-w", "--window",
1099 dest="window_size", default=None,
1100 help="window size, in # of messages, for calculating rate", metavar="WINDOW")
1101 options, args = parser.parse_args(args)
1102 if len(args) == 0:
1103 parser.error("topic must be specified")
1104 if len(args) > 1:
1105 parser.error("you may only specify one input topic")
1106 try:
1107 if options.window_size:
1108 import string
1109 window_size = string.atoi(options.window_size)
1110 else:
1111 window_size = options.window_size
1112 except:
1113 parser.error("window size must be an integer")
1114 topic = rosgraph.names.script_resolve_name('rostopic', args[0])
1115 _rostopic_bw(topic, window_size=window_size)
1116
1118 """
1119 Lookup topics by topic_type
1120 :param topic_type: type of topic to find, ``str``
1121 :returns: list of topic names that use topic_type, ``[str]``
1122 """
1123 master = rosgraph.Master('/rostopic')
1124 try:
1125 t_list = _master_get_topic_types(master)
1126 except socket.error:
1127 raise ROSTopicIOException("Unable to communicate with master!")
1128 return [t_name for t_name, t_type in t_list if t_type == topic_type]
1129
1131 """
1132 Implements 'rostopic type'
1133 :param argv: command-line args, ``[str]``
1134 """
1135 args = argv[2:]
1136 from optparse import OptionParser
1137 parser = OptionParser(usage="usage: %prog find msg-type", prog=NAME)
1138 options, args = parser.parse_args(args)
1139 if not len(args):
1140 parser.error("please specify a message type")
1141 if len(args) > 1:
1142 parser.error("you may only specify one message type")
1143 print('\n'.join(find_by_type(args[0])))
1144
1145
1147 """
1148 pkg/typeName -> pkg, typeName -> None
1149
1150 :param name: package resource name, e.g. 'std_msgs/String', ``str``
1151 :returns: package name of resource, ``str``
1152 """
1153 if not '/' in name:
1154 return None
1155 return name[:name.find('/')]
1156
1158 """
1159 Create rospy.Publisher instance from the string topic name and
1160 type. This is a powerful method as it allows creation of
1161 rospy.Publisher and Message instances using the topic and type
1162 names. This enables more dynamic publishing from Python programs.
1163
1164 :param topic_name: name of topic, ``str``
1165 :param topic_type: name of topic type, ``str``
1166 :param latch: latching topic, ``bool``
1167 :returns: topic :class:`rospy.Publisher`, :class:`Message` class
1168 """
1169 topic_name = rosgraph.names.script_resolve_name('rostopic', topic_name)
1170 try:
1171 msg_class = roslib.message.get_message_class(topic_type)
1172 except:
1173 raise ROSTopicException("invalid topic type: %s"%topic_type)
1174 if msg_class is None:
1175 pkg = _resource_name_package(topic_type)
1176 raise ROSTopicException("invalid message type: %s.\nIf this is a valid message type, perhaps you need to type 'rosmake %s'"%(topic_type, pkg))
1177
1178 rospy.init_node('rostopic', anonymous=True, disable_rosout=True, disable_rostime=True)
1179 pub = rospy.Publisher(topic_name, msg_class, latch=latch)
1180 return pub, msg_class
1181
1183 """
1184 Publish message at specified rate. Subroutine of L{publish_message()}.
1185
1186 :param pub: :class:rospy.Publisher` instance for topic
1187 :param msg: message instance to publish
1188 :param rate: publishing rate (hz) or None for just once, ``int``
1189 :param verbose: If ``True``, print more verbose output to stdout, ``bool``
1190 """
1191 try:
1192 r = rospy.Rate(float(rate))
1193 except ValueError:
1194 raise ROSTopicException("Rate must be a number")
1195 while not rospy.is_shutdown():
1196 if verbose:
1197 print("publishing %s"%msg)
1198 pub.publish(msg)
1199 r.sleep()
1200
1201 _ONCE_DELAY = 3.
1203 """
1204 Publish and latch message. Subroutine of L{publish_message()}.
1205
1206 :param pub: :class:`rospy.Publisher` instance for topic
1207 :param msg: message instance to publish
1208 :param once: if ``True``, publish message once and then exit after sleep interval, ``bool``
1209 :param verbose: If ``True``, print more verbose output to stdout, ``bool``
1210 """
1211 try:
1212 pub.publish(msg)
1213 except TypeError as e:
1214 raise ROSTopicException(str(e))
1215
1216 if not once:
1217 rospy.spin()
1218
1219 -def publish_message(pub, msg_class, pub_args, rate=None, once=False, verbose=False):
1220 """
1221 Create new instance of msg_class, populate with pub_args, and publish. This may
1222 print output to screen.
1223
1224 :param pub: :class:`rospy.Publisher` instance for topic
1225 :param msg_class: Message type, ``Class``
1226 :param pub_args: Arguments to initialize message that is published, ``[val]``
1227 :param rate: publishing rate (hz) or None for just once, ``int``
1228 :param once: publish only once and return, ``bool``
1229 :param verbose: If ``True``, print more verbose output to stdout, ``bool``
1230 """
1231 msg = msg_class()
1232 try:
1233
1234
1235
1236
1237
1238
1239
1240
1241
1242
1243
1244 now = rospy.get_rostime()
1245 import std_msgs.msg
1246 keys = { 'now': now, 'auto': std_msgs.msg.Header(stamp=now) }
1247 genpy.message.fill_message_args(msg, pub_args, keys=keys)
1248 except genpy.MessageException as e:
1249 raise ROSTopicException(str(e)+"\n\nArgs are: [%s]"%genpy.message.get_printable_message_args(msg))
1250 try:
1251
1252 if rate is None:
1253 s = "publishing and latching [%s]"%(msg) if verbose else "publishing and latching message"
1254 if once:
1255 s = s + " for %s seconds"%_ONCE_DELAY
1256 else:
1257 s = s + ". Press ctrl-C to terminate"
1258 print(s)
1259
1260 if rate is None:
1261 _publish_latched(pub, msg, once, verbose)
1262 else:
1263 _publish_at_rate(pub, msg, rate, verbose)
1264
1265 except rospy.ROSSerializationException as e:
1266 import rosmsg
1267
1268 raise ROSTopicException("Unable to publish message. One of the fields has an incorrect type:\n"+\
1269 " %s\n\nmsg file:\n%s"%(e, rosmsg.get_msg_text(msg_class._type)))
1270
1272 """
1273 Parse 'pub' command arguments and run command. Will cause a system
1274 exit if command-line argument parsing fails.
1275 :param argv: command-line arguments
1276 :param argv: [str]
1277 :raises: :exc:`ROSTopicException` If call command cannot be executed
1278 """
1279 args = argv[2:]
1280 from optparse import OptionParser
1281 parser = OptionParser(usage="usage: %prog pub /topic type [args...]", prog=NAME)
1282 parser.add_option("-v", dest="verbose", default=False,
1283 action="store_true",
1284 help="print verbose output")
1285 parser.add_option("-r", "--rate", dest="rate", default=None,
1286 help="publishing rate (hz). For -f and stdin input, this defaults to 10. Otherwise it is not set.")
1287 parser.add_option("-1", "--once", action="store_true", dest="once", default=False,
1288 help="publish one message and exit")
1289 parser.add_option("-f", '--file', dest="file", metavar='FILE', default=None,
1290 help="read args from YAML file (Bagy)")
1291 parser.add_option("-l", '--latch', dest="latch", default=False, action="store_true",
1292 help="enable latching for -f, -r and piped input. This latches the first message.")
1293
1294
1295
1296 (options, args) = parser.parse_args(args)
1297 if options.rate is not None:
1298 if options.once:
1299 parser.error("You cannot select both -r and -1 (--once)")
1300 try:
1301 rate = float(options.rate)
1302 except ValueError:
1303 parser.error("rate must be a number")
1304 if rate <= 0:
1305 parser.error("rate must be greater than zero")
1306 else:
1307
1308 rate = None
1309
1310
1311 if len(args) == 0:
1312 parser.error("/topic must be specified")
1313 if len(args) == 1:
1314 parser.error("topic type must be specified")
1315 if 0:
1316 if len(args) > 2 and options.parameter:
1317 parser.error("args confict with -p setting")
1318 if len(args) > 2 and options.file:
1319 parser.error("args confict with -f setting")
1320 topic_name, topic_type = args[0], args[1]
1321
1322
1323 try:
1324 pub_args = []
1325 for arg in args[2:]:
1326 pub_args.append(yaml.load(arg))
1327 except Exception as e:
1328 parser.error("Argument error: "+str(e))
1329
1330
1331
1332 _check_master()
1333
1334
1335 latch = (rate == None) or options.latch
1336 pub, msg_class = create_publisher(topic_name, topic_type, latch)
1337
1338 if 0 and options.parameter:
1339 param_name = rosgraph.names.script_resolve_name('rostopic', options.parameter)
1340 if options.once:
1341 param_publish_once(pub, msg_class, param_name, rate, options.verbose)
1342 else:
1343 param_publish(pub, msg_class, param_name, rate, options.verbose)
1344
1345 elif not pub_args and len(msg_class.__slots__):
1346 if not options.file and sys.stdin.isatty():
1347 parser.error("Please specify message values")
1348
1349 if rate is None and not options.latch and not options.once:
1350 rate = 10.
1351 stdin_publish(pub, msg_class, rate, options.once, options.file, options.verbose)
1352 else:
1353 argv_publish(pub, msg_class, pub_args, rate, options.once, options.verbose)
1354
1355
1357 """
1358 :param filename: file name, ``str``
1359 :returns: Iterator that yields pub args (list of args), ``iterator``
1360 :raises: :exc:`ROSTopicException` If filename is invalid
1361 """
1362 if not os.path.isfile(filename):
1363 raise ROSTopicException("file does not exist: %s"%(filename))
1364 import yaml
1365 def bagy_iter():
1366 try:
1367 with open(filename, 'r') as f:
1368
1369 data = yaml.load_all(f)
1370 for d in data:
1371 yield [d]
1372 except yaml.YAMLError as e:
1373 raise ROSTopicException("invalid YAML in file: %s"%(str(e)))
1374 return bagy_iter
1375
1376 -def argv_publish(pub, msg_class, pub_args, rate, once, verbose):
1377 publish_message(pub, msg_class, pub_args, rate, once, verbose=verbose)
1378
1379 if once:
1380
1381 timeout_t = time.time() + _ONCE_DELAY
1382 while not rospy.is_shutdown() and time.time() < timeout_t:
1383 rospy.sleep(0.2)
1384
1385 SUBSCRIBER_TIMEOUT = 5.
1387 timeout_t = time.time() + timeout
1388 while pub.get_num_connections() == 0 and timeout_t > time.time():
1389 _sleep(0.01)
1390
1392 if not rospy.has_param(param_name):
1393 raise ROSTopicException("parameter does not exist: %s"%(param_name))
1394 pub_args = rospy.get_param(param_name)
1395 argv_publish(pub, msg_class, pub_args, None, True, verbose)
1396
1397
1399
1400 - def __init__(self, param_name, value=None):
1401 import threading
1402 self.lock = threading.Condition()
1403 self.param_name = param_name
1404 self.updates = []
1405 self.value = None
1406
1408 with self.lock:
1409
1410 if key != self.param_name:
1411 subs = [x for x in key[len(self.param_name):].split('/') if x]
1412 idx = self.value
1413 for s in subs[:-1]:
1414 if s in idx:
1415 idx = idx[s]
1416 else:
1417 idx[s] = {}
1418 idx = idx[s]
1419 idx[subs[-1]] = value
1420 else:
1421 self.value = value
1422
1423 self.updates.append(self.value)
1424 self.lock.notify_all()
1425
1427 """
1428 :param param_name: ROS parameter name, ``str``
1429 :returns: List of msg dicts in file, ``[{str: any}]``
1430 :raises: :exc:`ROSTopicException` If parameter is not set
1431 """
1432 import rospy
1433 import rospy.impl.paramserver
1434 import rosgraph
1435
1436 if not rospy.has_param(param_name):
1437 raise ROSTopicException("parameter does not exist: %s"%(param_name))
1438
1439
1440
1441 ps_cache = rospy.impl.paramserver.get_param_server_cache()
1442 notifier = _ParamNotifier(param_name)
1443 ps_cache.set_notifier(notifier)
1444 master = rosgraph.Master(rospy.get_name())
1445 notifier.value = master.subscribeParam(rospy.get_node_uri(), param_name)
1446 pub_args = notifier.value
1447 ps_cache.set(param_name, pub_args)
1448 if type(pub_args) == dict:
1449 pub_args = [pub_args]
1450 elif type(pub_args) != list:
1451 raise ROSTopicException("Parameter [%s] in not a valid type"%(param_name))
1452
1453 r = rospy.Rate(rate) if rate is not None else None
1454 publish = True
1455 while not rospy.is_shutdown():
1456 try:
1457 if publish:
1458 publish_message(pub, msg_class, pub_args, None, True, verbose=verbose)
1459 except ValueError as e:
1460 sys.stderr.write("%s\n"%str(e))
1461 break
1462 if r is not None:
1463 r.sleep()
1464 with notifier.lock:
1465 if notifier.updates:
1466 pub_args = notifier.updates.pop(0)
1467 if type(pub_args) == dict:
1468 pub_args = [pub_args]
1469 else:
1470 publish = False
1471 with notifier.lock:
1472 if not notifier.updates:
1473 notifier.lock.wait(1.)
1474 if notifier.updates:
1475 publish = True
1476 pub_args = notifier.updates.pop(0)
1477 if type(pub_args) == dict:
1478 pub_args = [pub_args]
1479
1480 if rospy.is_shutdown():
1481 break
1482
1483 -def stdin_publish(pub, msg_class, rate, once, filename, verbose):
1484 """
1485 :param filename: name of file to read from instead of stdin, or ``None``, ``str``
1486 """
1487 if filename:
1488 iterator = file_yaml_arg(filename)
1489 else:
1490 iterator = stdin_yaml_arg
1491
1492 r = rospy.Rate(rate) if rate is not None else None
1493
1494
1495
1496
1497 wait_for_subscriber(pub, SUBSCRIBER_TIMEOUT)
1498
1499 single_arg = None
1500 for pub_args in iterator():
1501 if rospy.is_shutdown():
1502 break
1503 if pub_args:
1504 if type(pub_args) != list:
1505 pub_args = [pub_args]
1506 try:
1507
1508
1509
1510
1511
1512
1513
1514 publish_message(pub, msg_class, pub_args, None, bool(r) or once, verbose=verbose)
1515 except ValueError as e:
1516 sys.stderr.write("%s\n"%str(e))
1517 break
1518 if r is not None:
1519 r.sleep()
1520 if rospy.is_shutdown() or once:
1521 break
1522
1523
1524 if single_arg and r and not once:
1525 while not rospy.is_shutdown():
1526 try:
1527 publish_message(pub, msg_class, pub_args, None, True, verbose=verbose)
1528 if r is not None:
1529 r.sleep()
1530 except ValueError as e:
1531 break
1532
1534 """
1535 Iterate over YAML documents in stdin
1536 :returns: for next list of arguments on stdin. Iterator returns a list of args for each call, ``iterator``
1537 """
1538 import yaml
1539 from select import select
1540 from select import error as select_error
1541 try:
1542 arg = 'x'
1543 rlist = [sys.stdin]
1544 wlist = xlist = []
1545 while not rospy.is_shutdown() and arg != '\n':
1546 buff = ''
1547 while arg != '' and arg.strip() != '---' and not rospy.is_shutdown():
1548 val, _, _ = select(rlist, wlist, xlist, 1.0)
1549 if not val:
1550 continue
1551
1552 arg = sys.stdin.readline()
1553 if arg != '' and arg.strip() != '---':
1554 buff = buff + arg
1555
1556 if arg.strip() == '---':
1557 try:
1558 loaded = yaml.load(buff.rstrip())
1559 except Exception as e:
1560 sys.stderr.write("Invalid YAML: %s\n"%str(e))
1561 if loaded is not None:
1562 yield loaded
1563 elif arg == '':
1564
1565
1566 return
1567
1568 arg = 'x'
1569
1570 except select_error:
1571 return
1572
1574 """
1575 Command-line parsing for 'rostopic list' command.
1576 """
1577 args = argv[2:]
1578 from optparse import OptionParser
1579 parser = OptionParser(usage="usage: %prog list [/namespace]", prog=NAME)
1580 parser.add_option("-b", "--bag",
1581 dest="bag", default=None,
1582 help="list topics in .bag file", metavar="BAGFILE")
1583 parser.add_option("-v", "--verbose",
1584 dest="verbose", default=False,action="store_true",
1585 help="list full details about each topic")
1586 parser.add_option("-p",
1587 dest="publishers", default=False,action="store_true",
1588 help="list only publishers")
1589 parser.add_option("-s",
1590 dest="subscribers", default=False,action="store_true",
1591 help="list only subscribers")
1592 parser.add_option("--host", dest="hostname", default=False, action="store_true",
1593 help="group by host name")
1594
1595 (options, args) = parser.parse_args(args)
1596 topic = None
1597
1598 if len(args) == 1:
1599 topic = rosgraph.names.script_resolve_name('rostopic', args[0])
1600 elif len(args) > 1:
1601 parser.error("you may only specify one input topic")
1602 if options.bag:
1603 if options.subscribers:
1604 parser.error("-s option is not valid with bags")
1605 elif options.publishers:
1606 parser.error("-p option is not valid with bags")
1607 elif options.hostname:
1608 parser.error("--host option is not valid with bags")
1609 _rostopic_list_bag(options.bag, topic)
1610 else:
1611 if options.subscribers and options.publishers:
1612 parser.error("you may only specify one of -p, -s")
1613
1614 exitval = _rostopic_list(topic, verbose=options.verbose, subscribers_only=options.subscribers, publishers_only=options.publishers, group_by_host=options.hostname) or 0
1615 if exitval != 0:
1616 sys.exit(exitval)
1617
1619 """
1620 Command-line parsing for 'rostopic info' command.
1621 """
1622 args = argv[2:]
1623 from optparse import OptionParser
1624 parser = OptionParser(usage="usage: %prog info /topic", prog=NAME)
1625 (options, args) = parser.parse_args(args)
1626
1627 if len(args) == 0:
1628 parser.error("you must specify a topic name")
1629 elif len(args) > 1:
1630 parser.error("you may only specify one topic name")
1631
1632 topic = rosgraph.names.script_resolve_name('rostopic', args[0])
1633 exitval = _rostopic_info(topic) or 0
1634 if exitval != 0:
1635 sys.exit(exitval)
1636
1638 print("""rostopic is a command-line tool for printing information about ROS Topics.
1639
1640 Commands:
1641 \trostopic bw\tdisplay bandwidth used by topic
1642 \trostopic echo\tprint messages to screen
1643 \trostopic find\tfind topics by type
1644 \trostopic hz\tdisplay publishing rate of topic
1645 \trostopic info\tprint information about active topic
1646 \trostopic list\tlist active topics
1647 \trostopic pub\tpublish data to topic
1648 \trostopic type\tprint topic type
1649
1650 Type rostopic <command> -h for more detailed usage, e.g. 'rostopic echo -h'
1651 """)
1652 sys.exit(getattr(os, 'EX_USAGE', 1))
1653
1654 -def rostopicmain(argv=None):
1655 import rosbag
1656 if argv is None:
1657 argv=sys.argv
1658
1659 argv = rospy.myargv(argv)
1660
1661
1662 if len(argv) == 1:
1663 _fullusage()
1664 try:
1665 command = argv[1]
1666 if command == 'echo':
1667 _rostopic_cmd_echo(argv)
1668 elif command == 'hz':
1669 _rostopic_cmd_hz(argv)
1670 elif command == 'type':
1671 _rostopic_cmd_type(argv)
1672 elif command in 'list':
1673 _rostopic_cmd_list(argv)
1674 elif command == 'info':
1675 _rostopic_cmd_info(argv)
1676 elif command == 'pub':
1677 _rostopic_cmd_pub(argv)
1678 elif command == 'bw':
1679 _rostopic_cmd_bw(argv)
1680 elif command == 'find':
1681 _rostopic_cmd_find(argv)
1682 else:
1683 _fullusage()
1684 except socket.error:
1685 sys.stderr.write("Network communication failed. Most likely failed to communicate with master.\n")
1686 sys.exit(1)
1687 except rosbag.ROSBagException as e:
1688 sys.stderr.write("ERROR: unable to use bag file: %s\n"%str(e))
1689 sys.exit(1)
1690 except rosgraph.MasterException as e:
1691
1692 sys.stderr.write("ERROR: %s\n"%str(e))
1693 sys.exit(1)
1694 except ROSTopicException as e:
1695 sys.stderr.write("ERROR: %s\n"%str(e))
1696 sys.exit(1)
1697 except KeyboardInterrupt: pass
1698 except rospy.ROSInterruptException: pass
1699