Package roslib :: Module message
[frames] | no frames]

Source Code for Module roslib.message

  1  # Software License Agreement (BSD License) 
  2  # 
  3  # Copyright (c) 2008, Willow Garage, Inc. 
  4  # All rights reserved. 
  5  # 
  6  # Redistribution and use in source and binary forms, with or without 
  7  # modification, are permitted provided that the following conditions 
  8  # are met: 
  9  # 
 10  #  * Redistributions of source code must retain the above copyright 
 11  #    notice, this list of conditions and the following disclaimer. 
 12  #  * Redistributions in binary form must reproduce the above 
 13  #    copyright notice, this list of conditions and the following 
 14  #    disclaimer in the documentation and/or other materials provided 
 15  #    with the distribution. 
 16  #  * Neither the name of Willow Garage, Inc. nor the names of its 
 17  #    contributors may be used to endorse or promote products derived 
 18  #    from this software without specific prior written permission. 
 19  # 
 20  # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 
 21  # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 
 22  # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 
 23  # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 
 24  # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 
 25  # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 
 26  # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 
 27  # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 
 28  # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 
 29  # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 
 30  # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 
 31  # POSSIBILITY OF SUCH DAMAGE. 
 32  # 
 33  # Revision $Id: message.py 13381 2011-02-24 07:24:40Z kwc $ 
 34   
 35  """ 
 36  Support library for Python autogenerated message files. This defines 
 37  the L{Message} base class used by genmsg_py as well as support 
 38  libraries for type checking and retrieving message classes by type 
 39  name. 
 40  """ 
 41   
 42  import math 
 43  import itertools 
 44  import traceback 
 45  import struct 
 46   
 47  import roslib.exceptions 
 48  from roslib.rostime import Time, Duration, TVal 
 49   
 50  # common struct pattern singletons for msgs to use. Although this 
 51  # would better placed in a generator-specific module, we don't want to 
 52  # add another import to messages (which incurs higher import cost) 
 53  struct_I = struct.Struct('<I') 
 54   
55 -class ROSMessageException(roslib.exceptions.ROSLibException):
56 """ 57 Exception type for errors in roslib.message routines 58 """ 59 pass
60
61 -def _get_message_or_service_class(type_str, message_type, reload_on_error=False):
62 """ 63 Utility for retrieving message/service class instances. Used by 64 get_message_class and get_service_class. 65 @param type_str: 'msg' or 'srv' 66 @type type_str: str 67 @param message_type: type name of message/service 68 @type message_type: str 69 @return: Message/Service for message/service type or None 70 @rtype: class 71 @raise ValueError: if message_type is invalidly specified 72 """ 73 ## parse package and local type name for import 74 package, base_type = roslib.names.package_resource_name(message_type) 75 if not package: 76 if base_type == roslib.msgs.HEADER: 77 package = 'std_msgs' 78 else: 79 raise ValueError("message type is missing package name: %s"%str(message_type)) 80 pypkg = val = None 81 try: 82 # bootstrap our sys.path 83 roslib.launcher.load_manifest(package) 84 # import the package and return the class 85 pypkg = __import__('%s.%s'%(package, type_str)) 86 val = getattr(getattr(pypkg, type_str), base_type) 87 except roslib.packages.InvalidROSPkgException: 88 val = None 89 except ImportError: 90 val = None 91 except AttributeError: 92 val = None 93 94 # this logic is mainly to support rosh, so that a user doesn't 95 # have to exit a shell just because a message wasn't built yet 96 if val is None and reload_on_error: 97 try: 98 if pypkg: 99 reload(pypkg) 100 val = getattr(getattr(pypkg, type_str), base_type) 101 except: 102 val = None 103 return val
104 105 ## cache for get_message_class 106 _message_class_cache = {} 107
108 -def get_message_class(message_type, reload_on_error=False):
109 """ 110 Get the message class. NOTE: this function maintains a 111 local cache of results to improve performance. 112 @param message_type: type name of message 113 @type message_type: str 114 @param reload_on_error: (optional). Attempt to reload the Python 115 module if unable to load message the first time. Defaults to 116 False. This is necessary if messages are built after the first load. 117 @return: Message class for message/service type 118 @rtype: Message class 119 @raise ValueError: if message_type is invalidly specified 120 """ 121 if message_type in _message_class_cache: 122 return _message_class_cache[message_type] 123 cls = _get_message_or_service_class('msg', message_type, reload_on_error=reload_on_error) 124 if cls: 125 _message_class_cache[message_type] = cls 126 return cls
127 128 ## cache for get_service_class 129 _service_class_cache = {} 130
131 -def get_service_class(service_type, reload_on_error=False):
132 """ 133 Get the service class. NOTE: this function maintains a 134 local cache of results to improve performance. 135 @param service_type: type name of service 136 @type service_type: str 137 @param reload_on_error: (optional). Attempt to reload the Python 138 module if unable to load message the first time. Defaults to 139 False. This is necessary if messages are built after the first load. 140 @return: Service class for service type 141 @rtype: Service class 142 @raise Exception: if service_type is invalidly specified 143 """ 144 if service_type in _service_class_cache: 145 return _service_class_cache[service_type] 146 cls = _get_message_or_service_class('srv', service_type, reload_on_error=reload_on_error) 147 _service_class_cache[service_type] = cls 148 return cls
149 150 # we expose the generic message-strify routine for fn-oriented code like rostopic 151
152 -def strify_message(val, indent='', time_offset=None, current_time=None, field_filter=None):
153 """ 154 Convert value to string representation 155 @param val: to convert to string representation. Most likely a Message. 156 @type val: Value 157 @param indent: indentation. If indent is set, then the return value will have a leading \n 158 @type indent: str 159 @param time_offset: if not None, time fields will be displayed 160 as deltas from time_offset 161 @type time_offset: Time 162 @param current_time: currently not used. Only provided for API compatibility. current_time passes in the current time with respect to the message. 163 @type current_time: Time 164 @param field_filter: filter the fields that are strified for Messages. 165 @type field_filter: fn(Message)->iter(str) 166 @return: string (YAML) representation of message 167 @rtype: str 168 """ 169 type_ = type(val) 170 if type_ in (int, long, float, bool): 171 return str(val) 172 elif type_ in (str, unicode): 173 #TODO: need to escape strings correctly 174 if not val: 175 return "''" 176 return val 177 elif isinstance(val, TVal): 178 179 if time_offset is not None and isinstance(val, Time): 180 val = val-time_offset 181 182 return '\n%ssecs: %s\n%snsecs: %s'%(indent, val.secs, indent, val.nsecs) 183 184 elif type_ in (list, tuple): 185 if len(val) == 0: 186 return "[]" 187 val0 = val[0] 188 if type(val0) in (int, float, str, bool): 189 # TODO: escape strings properly 190 return str(list(val)) 191 else: 192 pref = indent + '- ' 193 indent = indent + ' ' 194 return '\n'+'\n'.join([pref+strify_message(v, indent, time_offset, current_time, field_filter) for v in val]) 195 elif isinstance(val, Message): 196 # allow caller to select which fields of message are strified 197 if field_filter is not None: 198 fields = list(field_filter(val)) 199 else: 200 fields = val.__slots__ 201 202 p = '%s%%s: %%s'%(indent) 203 ni = ' '+indent 204 vals = '\n'.join([p%(f, 205 strify_message(_convert_getattr(val, f, t), ni, time_offset, current_time, field_filter)) for f,t in itertools.izip(val.__slots__, val._slot_types) if f in fields]) 206 if indent: 207 return '\n'+vals 208 else: 209 return vals 210 211 else: 212 return str(val) #punt
213
214 -def _convert_getattr(val, f, t):
215 """ 216 Convert atttribute types on the fly, if necessary. This is mainly 217 to convert uint8[] fields back to an array type. 218 """ 219 attr = getattr(val, f) 220 if type(attr) in (str, unicode) and 'uint8[' in t: 221 return [ord(x) for x in attr] 222 else: 223 return attr
224 225 # check_type mildly violates some abstraction boundaries between .msg 226 # representation and the python Message representation. The 227 # alternative is to have the message generator map .msg types to 228 # python types beforehand, but that would make it harder to do 229 # width/signed checks. 230 231 _widths = { 232 'byte': 8, 'char': 8, 'int8': 8, 'uint8': 8, 233 'int16': 16, 'uint16': 16, 234 'int32': 32, 'uint32': 32, 235 'int64': 64, 'uint64': 64, 236 } 237
238 -def check_type(field_name, field_type, field_val):
239 """ 240 Dynamic type checker that maps ROS .msg types to python types and 241 verifies the python value. check_type() is not designed to be 242 fast and is targeted at error diagnosis. This type checker is not 243 designed to run fast and is meant only for error diagnosis. 244 245 @param field_name: ROS .msg field name 246 @type field_name: str 247 @param field_type: ROS .msg field type 248 @type field_type: str 249 @param field_val: field value 250 @type field_val: Any 251 @raise SerializationError: if typecheck fails 252 """ 253 # lazy-import as roslib.genpy has lots of extra imports. Would 254 # prefer to do lazy-init in a different manner 255 import roslib.genpy 256 if roslib.genpy.is_simple(field_type): 257 # check sign and width 258 if field_type in ['byte', 'int8', 'int16', 'int32', 'int64']: 259 if type(field_val) not in [long, int]: 260 raise SerializationError('field %s must be an integer type'%field_name) 261 maxval = int(math.pow(2, _widths[field_type]-1)) 262 if field_val >= maxval or field_val <= -maxval: 263 raise SerializationError('field %s exceeds specified width [%s]'%(field_name, field_type)) 264 elif field_type in ['char', 'uint8', 'uint16', 'uint32', 'uint64']: 265 if type(field_val) not in [long, int] or field_val < 0: 266 raise SerializationError('field %s must be unsigned integer type'%field_name) 267 maxval = int(math.pow(2, _widths[field_type])) 268 if field_val >= maxval: 269 raise SerializationError('field %s exceeds specified width [%s]'%(field_name, field_type)) 270 elif field_type == 'bool': 271 if field_val not in [True, False, 0, 1]: 272 raise SerializationError('field %s is not a bool'%(field_name)) 273 elif field_type == 'string': 274 if type(field_val) == unicode: 275 raise SerializationError('field %s is a unicode string instead of an ascii string'%field_name) 276 elif type(field_val) != str: 277 raise SerializationError('field %s must be of type str'%field_name) 278 elif field_type == 'time': 279 if not isinstance(field_val, Time): 280 raise SerializationError('field %s must be of type Time'%field_name) 281 elif field_type == 'duration': 282 if not isinstance(field_val, Duration): 283 raise SerializationError('field %s must be of type Duration'%field_name) 284 285 elif field_type.endswith(']'): # array type 286 # use index to generate error if '[' not present 287 base_type = field_type[:field_type.index('[')] 288 289 if type(field_val) == str: 290 if not base_type in ['char', 'uint8']: 291 raise SerializationError('field %s must be a list or tuple type. Only uint8[] can be a string' % field_name); 292 else: 293 #It's a string so its already in byte format and we 294 #don't need to check the individual bytes in the 295 #string. 296 return 297 298 if not type(field_val) in [list, tuple]: 299 raise SerializationError('field %s must be a list or tuple type'%field_name) 300 for v in field_val: 301 check_type(field_name+"[]", base_type, v) 302 else: 303 if isinstance(field_val, Message): 304 # roslib/Header is the old location of Header. We check it for backwards compat 305 if field_val._type in ['std_msgs/Header', 'roslib/Header']: 306 if field_type not in ['Header', 'std_msgs/Header', 'roslib/Header']: 307 raise SerializationError("field %s must be a Header instead of a %s"%(field_name, field_val._type)) 308 elif field_val._type != field_type: 309 raise SerializationError("field %s must be of type %s instead of %s"%(field_name, field_type, field_val._type)) 310 for n, t in zip(field_val.__slots__, field_val._get_types()): 311 check_type("%s.%s"%(field_name,n), t, getattr(field_val, n)) 312 else: 313 raise SerializationError("field %s must be of type [%s]"%(field_name, field_type))
314 315 #TODO: dynamically load message class and do instance compare 316
317 -class Message(object):
318 """Base class of Message data classes auto-generated from msg files. """ 319 320 # slots is explicitly both for data representation and 321 # performance. Higher-level code assumes that there is a 1-to-1 322 # mapping between __slots__ and message fields. In terms of 323 # performance, explicitly settings slots eliminates dictionary for 324 # new-style object. 325 __slots__ = ['_connection_header'] 326
327 - def __init__(self, *args, **kwds):
328 """ 329 Create a new Message instance. There are multiple ways of 330 initializing Message instances, either using a 1-to-1 331 correspondence between constructor arguments and message 332 fields (*args), or using Python "keyword" arguments (**kwds) to initialize named field 333 and leave the rest with default values. 334 """ 335 if args and kwds: 336 raise TypeError("Message constructor may only use args OR keywords, not both") 337 if args: 338 if len(args) != len(self.__slots__): 339 raise TypeError, "Invalid number of arguments, args should be %s"%str(self.__slots__)+" args are"+str(args) 340 for i, k in enumerate(self.__slots__): 341 setattr(self, k, args[i]) 342 else: 343 # validate kwds 344 for k,v in kwds.iteritems(): 345 if not k in self.__slots__: 346 raise AttributeError("%s is not an attribute of %s"%(k, self.__class__.__name__)) 347 # iterate through slots so all fields are initialized. 348 # this is important so that subclasses don't reference an 349 # uninitialized field and raise an AttributeError. 350 for k in self.__slots__: 351 if k in kwds: 352 setattr(self, k, kwds[k]) 353 else: 354 setattr(self, k, None)
355
356 - def __getstate__(self):
357 """ 358 support for Python pickling 359 """ 360 return [getattr(self, x) for x in self.__slots__]
361
362 - def __setstate__(self, state):
363 """ 364 support for Python pickling 365 """ 366 for x, val in itertools.izip(self.__slots__, state): 367 setattr(self, x, val)
368
369 - def _get_types(self):
370 raise Exception("must be overriden")
371 - def _check_types(self, exc=None):
372 """ 373 Perform dynamic type-checking of Message fields. This is performance intensive 374 and is meant for post-error diagnosis 375 @param exc: underlying exception that gave cause for type check. 376 @type exc: Exception 377 @raise roslib.messages.SerializationError: if typecheck fails 378 """ 379 for n, t in zip(self.__slots__, self._get_types()): 380 check_type(n, t, getattr(self, n)) 381 if exc: # if exc is set and check_type could not diagnose, raise wrapped error 382 raise SerializationError(str(exc))
383
384 - def serialize(self, buff):
385 """ 386 Serialize data into buffer 387 @param buff: buffer 388 @type buff: StringIO 389 """ 390 pass
391 - def deserialize(self, str):
392 """ 393 Deserialize data in str into this instance 394 @param str: serialized data 395 @type str: str 396 """ 397 pass
398 - def __repr__(self):
399 return strify_message(self)
400 - def __str__(self):
401 return strify_message(self)
402 # TODO: unit test
403 - def __eq__(self, other):
404 if not isinstance(other, self.__class__): 405 return False 406 for f in self.__slots__: 407 try: 408 v1 = getattr(self, f) 409 v2 = getattr(other, f) 410 if type(v1) in (list, tuple) and type(v2) in (list, tuple): 411 # we treat tuples and lists as equivalent 412 if tuple(v1) != tuple(v2): 413 return False 414 elif not v1 == v2: 415 return False 416 except AttributeError: 417 return False 418 return True
419
420 -class ServiceDefinition(object):
421 """Base class of Service classes auto-generated from srv files""" 422 pass
423
424 -class DeserializationError(ROSMessageException):
425 """Message deserialization error""" 426 pass
427 -class SerializationError(ROSMessageException):
428 """Message serialization error""" 429 pass
430 431 # Utilities for rostopic/rosservice 432
433 -def get_printable_message_args(msg, buff=None, prefix=''):
434 """ 435 Get string representation of msg arguments 436 @param msg: msg message to fill 437 @type msg: Message 438 @param prefix: field name prefix (for verbose printing) 439 @type prefix: str 440 @return: printable representation of msg args 441 @rtype: str 442 """ 443 import cStringIO 444 if buff is None: 445 buff = cStringIO.StringIO() 446 for f in msg.__slots__: 447 if isinstance(getattr(msg, f), Message): 448 get_printable_message_args(getattr(msg, f), buff=buff, prefix=(prefix+f+'.')) 449 else: 450 buff.write(prefix+f+' ') 451 return buff.getvalue().rstrip()
452
453 -def _fill_val(msg, f, v, keys, prefix):
454 """ 455 Subroutine of L{_fill_message_args()}. Sets a particular field on a message 456 @param f: field name 457 @type f: str 458 @param v: field value 459 @param keys: keys to use as substitute values for messages and timestamps. 460 @type keys: dict 461 """ 462 if not f in msg.__slots__: 463 raise ROSMessageException("No field name [%s%s]"%(prefix, f)) 464 def_val = getattr(msg, f) 465 if isinstance(def_val, Message) or isinstance(def_val, roslib.rostime.TVal): 466 # check for substitution key, e.g. 'now' 467 if type(v) == str: 468 if v in keys: 469 setattr(msg, f, keys[v]) 470 else: 471 raise ROSMessageException("No key named [%s]"%(v)) 472 elif isinstance(def_val, roslib.rostime.TVal) and type(v) in (int, long): 473 #special case to handle time value represented as a single number 474 #TODO: this is a lossy conversion 475 if isinstance(def_val, roslib.rostime.Time): 476 setattr(msg, f, roslib.rostime.Time.from_sec(v/1e9)) 477 elif isinstance(def_val, roslib.rostime.Duration): 478 setattr(msg, f, roslib.rostime.Duration.from_sec(v/1e9)) 479 else: 480 raise ROSMessageException("Cannot create time values of type [%s]"%(type(def_val))) 481 else: 482 _fill_message_args(def_val, v, keys, prefix=(prefix+f+'.')) 483 elif type(def_val) == list: 484 if not type(v) in [list, tuple]: 485 raise ROSMessageException("Field [%s%s] must be a list or tuple instead of: %s"%(prefix, f, type(v).__name__)) 486 # determine base_type of field by looking at _slot_types 487 idx = msg.__slots__.index(f) 488 t = msg._slot_types[idx] 489 base_type = roslib.msgs.base_msg_type(t) 490 # - for primitives, we just directly set (we don't 491 # type-check. we rely on serialization type checker) 492 if base_type in roslib.msgs.PRIMITIVE_TYPES: 493 setattr(msg, f, v) 494 495 # - for complex types, we have to iteratively append to def_val 496 else: 497 list_msg_class = get_message_class(base_type) 498 for el in v: 499 inner_msg = list_msg_class() 500 _fill_message_args(inner_msg, el, prefix) 501 def_val.append(inner_msg) 502 else: 503 #print "SET2", f, v 504 setattr(msg, f, v)
505 506
507 -def _fill_message_args(msg, msg_args, keys, prefix=''):
508 """ 509 Populate message with specified args. 510 511 @param msg: message to fill 512 @type msg: Message 513 @param msg_args: list of arguments to set fields to 514 @type msg_args: [args] 515 @param keys: keys to use as substitute values for messages and timestamps. 516 @type keys: dict 517 @param prefix: field name prefix (for verbose printing) 518 @type prefix: str 519 @return: unused/leftover message arguments. 520 @rtype: [args] 521 @raise ROSMessageException: if not enough message arguments to fill message 522 @raise ValueError: if msg or msg_args is not of correct type 523 """ 524 if not isinstance(msg, (Message, roslib.rostime.TVal)): 525 raise ValueError("msg must be a Message instance: %s"%msg) 526 527 if type(msg_args) == dict: 528 529 #print "DICT ARGS", msg_args 530 #print "ACTIVE SLOTS",msg.__slots__ 531 532 for f, v in msg_args.iteritems(): 533 # assume that an empty key is actually an empty string 534 if v == None: 535 v = '' 536 _fill_val(msg, f, v, keys, prefix) 537 elif type(msg_args) == list: 538 539 #print "LIST ARGS", msg_args 540 #print "ACTIVE SLOTS",msg.__slots__ 541 542 if len(msg_args) > len(msg.__slots__): 543 raise ROSMessageException("Too many arguments:\n * Given: %s\n * Expected: %s"%(msg_args, msg.__slots__)) 544 elif len(msg_args) < len(msg.__slots__): 545 raise ROSMessageException("Not enough arguments:\n * Given: %s\n * Expected: %s"%(msg_args, msg.__slots__)) 546 547 for f, v in itertools.izip(msg.__slots__, msg_args): 548 _fill_val(msg, f, v, keys, prefix) 549 else: 550 raise ValueError("invalid msg_args type: %s"%str(msg_args))
551
552 -def fill_message_args(msg, msg_args, keys={}):
553 """ 554 Populate message with specified args. Args are assumed to be a 555 list of arguments from a command-line YAML parser. See 556 http://www.ros.org/wiki/ROS/YAMLCommandLine for specification on 557 how messages are filled. 558 559 fill_message_args also takes in an optional 'keys' dictionary 560 which contain substitute values for message and time types. These 561 values must be of the correct instance type, i.e. a Message, Time, 562 or Duration. In a string key is encountered with these types, the 563 value from the keys dictionary will be used instead. This is 564 mainly used to provide values for the 'now' timestamp. 565 566 @param msg: message to fill 567 @type msg: Message 568 569 @param msg_args: list of arguments to set fields to, or 570 If None, msg_args will be made an empty list. 571 @type msg_args: [args] 572 573 @param keys: keys to use as substitute values for messages and timestamps. 574 @type keys: dict 575 @raise ROSMessageException: if not enough/too many message arguments to fill message 576 """ 577 # a list of arguments is similar to python's 578 # *args, whereas dictionaries are like **kwds. 579 580 # empty messages serialize as a None, which we make equivalent to 581 # an empty message 582 if msg_args is None: 583 msg_args = [] 584 585 # msg_args is always a list, due to the fact it is parsed from a 586 # command-line argument list. We have to special-case handle a 587 # list with a single dictionary, which has precedence over the 588 # general list representation. We offer this precedence as there 589 # is no other way to do kwd assignments into the outer message. 590 if len(msg_args) == 1 and type(msg_args[0]) == dict: 591 # according to spec, if we only get one msg_arg and it's a dictionary, we 592 # use it directly 593 _fill_message_args(msg, msg_args[0], keys, '') 594 else: 595 _fill_message_args(msg, msg_args, keys, '')
596