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 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 import sys
47
48 import roslib.exceptions
49 from roslib.rostime import Time, Duration, TVal
50
51
52
53
54
55 if sys.version > '3':
56 long = int
57
58 struct_I = struct.Struct('<I')
59
61 """Small helper version to check an object is a string in a way that works
62 for both Python 2 and 3
63 """
64 try:
65 return isinstance(s, basestring)
66 except NameError:
67 return isinstance(s, str)
68
70 """
71 Exception type for errors in roslib.message routines
72 """
73 pass
74
76 """
77 Utility for retrieving message/service class instances. Used by
78 get_message_class and get_service_class.
79 @param type_str: 'msg' or 'srv'
80 @type type_str: str
81 @param message_type: type name of message/service
82 @type message_type: str
83 @return: Message/Service for message/service type or None
84 @rtype: class
85 @raise ValueError: if message_type is invalidly specified
86 """
87
88 package, base_type = roslib.names.package_resource_name(message_type)
89 if not package:
90 if base_type == roslib.msgs.HEADER:
91 package = 'std_msgs'
92 else:
93 raise ValueError("message type is missing package name: %s"%str(message_type))
94 pypkg = val = None
95 try:
96
97 roslib.launcher.load_manifest(package)
98
99 pypkg = __import__('%s.%s'%(package, type_str))
100 val = getattr(getattr(pypkg, type_str), base_type)
101 except roslib.packages.InvalidROSPkgException:
102 val = None
103 except ImportError:
104 val = None
105 except AttributeError:
106 val = None
107
108
109
110 if val is None and reload_on_error:
111 try:
112 if pypkg:
113 reload(pypkg)
114 val = getattr(getattr(pypkg, type_str), base_type)
115 except:
116 val = None
117 return val
118
119
120 _message_class_cache = {}
121
123 """
124 Get the message class. NOTE: this function maintains a
125 local cache of results to improve performance.
126 @param message_type: type name of message
127 @type message_type: str
128 @param reload_on_error: (optional). Attempt to reload the Python
129 module if unable to load message the first time. Defaults to
130 False. This is necessary if messages are built after the first load.
131 @return: Message class for message/service type
132 @rtype: Message class
133 @raise ValueError: if message_type is invalidly specified
134 """
135 if message_type in _message_class_cache:
136 return _message_class_cache[message_type]
137 cls = _get_message_or_service_class('msg', message_type, reload_on_error=reload_on_error)
138 if cls:
139 _message_class_cache[message_type] = cls
140 return cls
141
142
143 _service_class_cache = {}
144
146 """
147 Get the service class. NOTE: this function maintains a
148 local cache of results to improve performance.
149 @param service_type: type name of service
150 @type service_type: str
151 @param reload_on_error: (optional). Attempt to reload the Python
152 module if unable to load message the first time. Defaults to
153 False. This is necessary if messages are built after the first load.
154 @return: Service class for service type
155 @rtype: Service class
156 @raise Exception: if service_type is invalidly specified
157 """
158 if service_type in _service_class_cache:
159 return _service_class_cache[service_type]
160 cls = _get_message_or_service_class('srv', service_type, reload_on_error=reload_on_error)
161 _service_class_cache[service_type] = cls
162 return cls
163
164
165
166 -def strify_message(val, indent='', time_offset=None, current_time=None, field_filter=None):
167 """
168 Convert value to string representation
169 @param val: to convert to string representation. Most likely a Message.
170 @type val: Value
171 @param indent: indentation. If indent is set, then the return value will have a leading \n
172 @type indent: str
173 @param time_offset: if not None, time fields will be displayed
174 as deltas from time_offset
175 @type time_offset: Time
176 @param current_time: currently not used. Only provided for API compatibility. current_time passes in the current time with respect to the message.
177 @type current_time: Time
178 @param field_filter: filter the fields that are strified for Messages.
179 @type field_filter: fn(Message)->iter(str)
180 @return: string (YAML) representation of message
181 @rtype: str
182 """
183
184 type_ = type(val)
185 if type_ in (int, long, float, bool):
186 return str(val)
187 elif isstring(val):
188
189 if not val:
190 return "''"
191 return val
192 elif isinstance(val, TVal):
193
194 if time_offset is not None and isinstance(val, Time):
195 val = val-time_offset
196
197 return '\n%ssecs: %s\n%snsecs: %s'%(indent, val.secs, indent, val.nsecs)
198
199 elif type_ in (list, tuple):
200 if len(val) == 0:
201 return "[]"
202 val0 = val[0]
203 if type(val0) in (int, float, str, bool):
204
205 return str(list(val))
206 else:
207 pref = indent + '- '
208 indent = indent + ' '
209 return '\n'+'\n'.join([pref+strify_message(v, indent, time_offset, current_time, field_filter) for v in val])
210 elif isinstance(val, Message):
211
212 if field_filter is not None:
213 fields = list(field_filter(val))
214 else:
215 fields = val.__slots__
216
217 p = '%s%%s: %%s'%(indent)
218 ni = ' '+indent
219 if sys.hexversion > 0x03000000:
220 vals = '\n'.join([p%(f,
221 strify_message(_convert_getattr(val, f, t), ni, time_offset, current_time, field_filter)) for f,t in zip(val.__slots__, val._slot_types) if f in fields])
222 else:
223 vals = '\n'.join([p%(f,
224 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])
225 if indent:
226 return '\n'+vals
227 else:
228 return vals
229
230 else:
231 return str(val)
232
234 """
235 Convert atttribute types on the fly, if necessary. This is mainly
236 to convert uint8[] fields back to an array type.
237 """
238 attr = getattr(val, f)
239 if isstring(attr) and 'uint8[' in t:
240 return [ord(x) for x in attr]
241 else:
242 return attr
243
244
245
246
247
248
249
250 _widths = {
251 'byte': 8, 'char': 8, 'int8': 8, 'uint8': 8,
252 'int16': 16, 'uint16': 16,
253 'int32': 32, 'uint32': 32,
254 'int64': 64, 'uint64': 64,
255 }
256
257 -def check_type(field_name, field_type, field_val):
258 """
259 Dynamic type checker that maps ROS .msg types to python types and
260 verifies the python value. check_type() is not designed to be
261 fast and is targeted at error diagnosis. This type checker is not
262 designed to run fast and is meant only for error diagnosis.
263
264 @param field_name: ROS .msg field name
265 @type field_name: str
266 @param field_type: ROS .msg field type
267 @type field_type: str
268 @param field_val: field value
269 @type field_val: Any
270 @raise SerializationError: if typecheck fails
271 """
272
273
274 import roslib.genpy
275 if roslib.genpy.is_simple(field_type):
276
277 if field_type in ['byte', 'int8', 'int16', 'int32', 'int64']:
278 if type(field_val) not in [long, int]:
279 raise SerializationError('field %s must be an integer type'%field_name)
280 maxval = int(math.pow(2, _widths[field_type]-1))
281 if field_val >= maxval or field_val <= -maxval:
282 raise SerializationError('field %s exceeds specified width [%s]'%(field_name, field_type))
283 elif field_type in ['char', 'uint8', 'uint16', 'uint32', 'uint64']:
284 if type(field_val) not in [long, int] or field_val < 0:
285 raise SerializationError('field %s must be unsigned integer type'%field_name)
286 maxval = int(math.pow(2, _widths[field_type]))
287 if field_val >= maxval:
288 raise SerializationError('field %s exceeds specified width [%s]'%(field_name, field_type))
289 elif field_type == 'bool':
290 if field_val not in [True, False, 0, 1]:
291 raise SerializationError('field %s is not a bool'%(field_name))
292 elif field_type == 'string':
293 if sys.hexversion > 0x03000000:
294 if type(field_val) == str:
295 raise SerializationError('field %s is a unicode string instead of an ascii string'%field_name)
296 else:
297 if type(field_val) == unicode:
298 raise SerializationError('field %s is a unicode string instead of an ascii string'%field_name)
299 elif not isstring(field_val):
300 raise SerializationError('field %s must be of type str'%field_name)
301 elif field_type == 'time':
302 if not isinstance(field_val, Time):
303 raise SerializationError('field %s must be of type Time'%field_name)
304 elif field_type == 'duration':
305 if not isinstance(field_val, Duration):
306 raise SerializationError('field %s must be of type Duration'%field_name)
307
308 elif field_type.endswith(']'):
309
310 base_type = field_type[:field_type.index('[')]
311
312 if type(field_val) == str:
313 if not base_type in ['char', 'uint8']:
314 raise SerializationError('field %s must be a list or tuple type. Only uint8[] can be a string' % field_name);
315 else:
316
317
318
319 return
320
321 if not type(field_val) in [list, tuple]:
322 raise SerializationError('field %s must be a list or tuple type'%field_name)
323 for v in field_val:
324 check_type(field_name+"[]", base_type, v)
325 else:
326 if isinstance(field_val, Message):
327
328 if field_val._type in ['std_msgs/Header', 'roslib/Header']:
329 if field_type not in ['Header', 'std_msgs/Header', 'roslib/Header']:
330 raise SerializationError("field %s must be a Header instead of a %s"%(field_name, field_val._type))
331 elif field_val._type != field_type:
332 raise SerializationError("field %s must be of type %s instead of %s"%(field_name, field_type, field_val._type))
333 for n, t in zip(field_val.__slots__, field_val._get_types()):
334 check_type("%s.%s"%(field_name,n), t, getattr(field_val, n))
335 else:
336 raise SerializationError("field %s must be of type [%s]"%(field_name, field_type))
337
338
339
341 """Base class of Message data classes auto-generated from msg files. """
342
343
344
345
346
347
348 __slots__ = ['_connection_header']
349
351 """
352 Create a new Message instance. There are multiple ways of
353 initializing Message instances, either using a 1-to-1
354 correspondence between constructor arguments and message
355 fields (*args), or using Python "keyword" arguments (**kwds) to initialize named field
356 and leave the rest with default values.
357 """
358 if args and kwds:
359 raise TypeError("Message constructor may only use args OR keywords, not both")
360 if args:
361 if len(args) != len(self.__slots__):
362 raise TypeError("Invalid number of arguments, args should be %s"%str(self.__slots__)+" args are"+str(args))
363 for i, k in enumerate(self.__slots__):
364 setattr(self, k, args[i])
365 else:
366
367 for k,v in kwds.items():
368 if not k in self.__slots__:
369 raise AttributeError("%s is not an attribute of %s"%(k, self.__class__.__name__))
370
371
372
373 for k in self.__slots__:
374 if k in kwds:
375 setattr(self, k, kwds[k])
376 else:
377 setattr(self, k, None)
378
380 """
381 support for Python pickling
382 """
383 return [getattr(self, x) for x in self.__slots__]
384
386 """
387 support for Python pickling
388 """
389 for x, val in zip(self.__slots__, state):
390 setattr(self, x, val)
391
393 raise Exception("must be overriden")
395 """
396 Perform dynamic type-checking of Message fields. This is performance intensive
397 and is meant for post-error diagnosis
398 @param exc: underlying exception that gave cause for type check.
399 @type exc: Exception
400 @raise roslib.messages.SerializationError: if typecheck fails
401 """
402 for n, t in zip(self.__slots__, self._get_types()):
403 check_type(n, t, getattr(self, n))
404 if exc:
405 raise SerializationError(str(exc))
406
408 """
409 Serialize data into buffer
410 @param buff: buffer
411 @type buff: StringIO
412 """
413 pass
415 """
416 Deserialize data in str into this instance
417 @param str: serialized data
418 @type str: str
419 """
420 pass
425
427 if not isinstance(other, self.__class__):
428 return False
429 for f in self.__slots__:
430 try:
431 v1 = getattr(self, f)
432 v2 = getattr(other, f)
433 if type(v1) in (list, tuple) and type(v2) in (list, tuple):
434
435 if tuple(v1) != tuple(v2):
436 return False
437 elif not v1 == v2:
438 return False
439 except AttributeError:
440 return False
441 return True
442
444 """Base class of Service classes auto-generated from srv files"""
445 pass
446
448 """Message deserialization error"""
449 pass
451 """Message serialization error"""
452 pass
453
454
455
457 """
458 Get string representation of msg arguments
459 @param msg: msg message to fill
460 @type msg: Message
461 @param prefix: field name prefix (for verbose printing)
462 @type prefix: str
463 @return: printable representation of msg args
464 @rtype: str
465 """
466 try:
467 from cStringIO import StringIO
468 python3 = 0
469 except ImportError:
470 from io import BytesIO
471 python3 = 1
472
473 if buff is None:
474 if python3 == 1:
475 buff = BytesIO()
476 else:
477 buff = StringIO()
478 for f in msg.__slots__:
479 if isinstance(getattr(msg, f), Message):
480 get_printable_message_args(getattr(msg, f), buff=buff, prefix=(prefix+f+'.'))
481 else:
482 buff.write(prefix+f+' ')
483 return buff.getvalue().rstrip()
484
486 """
487 Subroutine of L{_fill_message_args()}. Sets a particular field on a message
488 @param f: field name
489 @type f: str
490 @param v: field value
491 @param keys: keys to use as substitute values for messages and timestamps.
492 @type keys: dict
493 """
494 if not f in msg.__slots__:
495 raise ROSMessageException("No field name [%s%s]"%(prefix, f))
496 def_val = getattr(msg, f)
497 if isinstance(def_val, Message) or isinstance(def_val, roslib.rostime.TVal):
498
499 if type(v) == str:
500 if v in keys:
501 setattr(msg, f, keys[v])
502 else:
503 raise ROSMessageException("No key named [%s]"%(v))
504 elif isinstance(def_val, roslib.rostime.TVal) and type(v) in (int, long):
505
506
507 if isinstance(def_val, roslib.rostime.Time):
508 setattr(msg, f, roslib.rostime.Time.from_sec(v/1e9))
509 elif isinstance(def_val, roslib.rostime.Duration):
510 setattr(msg, f, roslib.rostime.Duration.from_sec(v/1e9))
511 else:
512 raise ROSMessageException("Cannot create time values of type [%s]"%(type(def_val)))
513 else:
514 _fill_message_args(def_val, v, keys, prefix=(prefix+f+'.'))
515 elif type(def_val) == list:
516 if not type(v) in [list, tuple]:
517 raise ROSMessageException("Field [%s%s] must be a list or tuple instead of: %s"%(prefix, f, type(v).__name__))
518
519 idx = msg.__slots__.index(f)
520 t = msg._slot_types[idx]
521 base_type, is_array, length = roslib.msgs.parse_type(t)
522
523
524 if base_type in roslib.msgs.PRIMITIVE_TYPES:
525
526 if length is not None and len(v) != length:
527 raise ROSMessageException("Field [%s%s] has incorrect number of elements: %s != %s"%(prefix, f, len(v), length))
528 setattr(msg, f, v)
529
530
531 else:
532
533 if length is not None and len(v) != length:
534 raise ROSMessageException("Field [%s%s] has incorrect number of elements: %s != %s"%(prefix, f, len(v), length))
535 list_msg_class = get_message_class(base_type)
536 if list_msg_class is None:
537 raise ROSMessageException("Cannot instantiate messages for field [%s%s] : cannot load class %s"%(prefix, f, base_type))
538 del def_val[:]
539 for el in v:
540 inner_msg = list_msg_class()
541 _fill_message_args(inner_msg, el, prefix)
542 def_val.append(inner_msg)
543 else:
544
545 setattr(msg, f, v)
546
547
549 """
550 Populate message with specified args.
551
552 @param msg: message to fill
553 @type msg: Message
554 @param msg_args: list of arguments to set fields to
555 @type msg_args: [args]
556 @param keys: keys to use as substitute values for messages and timestamps.
557 @type keys: dict
558 @param prefix: field name prefix (for verbose printing)
559 @type prefix: str
560 @return: unused/leftover message arguments.
561 @rtype: [args]
562 @raise ROSMessageException: if not enough message arguments to fill message
563 @raise ValueError: if msg or msg_args is not of correct type
564 """
565 if not isinstance(msg, (Message, roslib.rostime.TVal)):
566 raise ValueError("msg must be a Message instance: %s"%msg)
567
568 if type(msg_args) == dict:
569
570
571
572
573 for f, v in msg_args.items():
574
575 if v == None:
576 v = ''
577 _fill_val(msg, f, v, keys, prefix)
578 elif type(msg_args) == list:
579
580
581
582
583 if len(msg_args) > len(msg.__slots__):
584 raise ROSMessageException("Too many arguments:\n * Given: %s\n * Expected: %s"%(msg_args, msg.__slots__))
585 elif len(msg_args) < len(msg.__slots__):
586 raise ROSMessageException("Not enough arguments:\n * Given: %s\n * Expected: %s"%(msg_args, msg.__slots__))
587
588 for f, v in zip(msg.__slots__, msg_args):
589 _fill_val(msg, f, v, keys, prefix)
590 else:
591 raise ValueError("invalid msg_args type: %s"%str(msg_args))
592
594 """
595 Populate message with specified args. Args are assumed to be a
596 list of arguments from a command-line YAML parser. See
597 http://www.ros.org/wiki/ROS/YAMLCommandLine for specification on
598 how messages are filled.
599
600 fill_message_args also takes in an optional 'keys' dictionary
601 which contain substitute values for message and time types. These
602 values must be of the correct instance type, i.e. a Message, Time,
603 or Duration. In a string key is encountered with these types, the
604 value from the keys dictionary will be used instead. This is
605 mainly used to provide values for the 'now' timestamp.
606
607 @param msg: message to fill
608 @type msg: Message
609
610 @param msg_args: list of arguments to set fields to, or
611 If None, msg_args will be made an empty list.
612 @type msg_args: [args]
613
614 @param keys: keys to use as substitute values for messages and timestamps.
615 @type keys: dict
616 @raise ROSMessageException: if not enough/too many message arguments to fill message
617 """
618
619
620
621
622
623 if msg_args is None:
624 msg_args = []
625
626
627
628
629
630
631 if len(msg_args) == 1 and type(msg_args[0]) == dict:
632
633
634 _fill_message_args(msg, msg_args[0], keys, '')
635 else:
636 _fill_message_args(msg, msg_args, keys, '')
637