Module rostopic

Source Code for Module rostopic

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