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