cbor_conversion.py
Go to the documentation of this file.
1 import struct
2 import sys
3 
4 PYTHON2 = sys.version_info < (3, 0)
5 
6 try:
7  from cbor import Tag
8 except ImportError:
9  from rosbridge_library.util.cbor import Tag
10 
11 
12 LIST_TYPES = [list, tuple]
13 INT_TYPES = ['byte', 'char', 'int8', 'uint8', 'int16', 'uint16', 'int32', 'uint32', 'int64', 'uint64']
14 FLOAT_TYPES = ['float32', 'float64']
15 STRING_TYPES = ['string']
16 BOOL_TYPES = ['bool']
17 TIME_TYPES = ['time', 'duration']
18 BOOL_ARRAY_TYPES = ['bool[]']
19 BYTESTREAM_TYPES = ['uint8[]', 'char[]']
20 
21 # Typed array tags according to <https://tools.ietf.org/html/draft-ietf-cbor-array-tags-00>
22 # Always encode to little-endian variant, for now.
23 TAGGED_ARRAY_FORMATS = {
24  'uint16[]': (69, '<{}H'),
25  'uint32[]': (70, '<{}I'),
26  'uint64[]': (71, '<{}Q'),
27  'byte[]': (72, '{}b'),
28  'int8[]': (72, '{}b'),
29  'int16[]': (77, '<{}h'),
30  'int32[]': (78, '<{}i'),
31  'int64[]': (79, '<{}q'),
32  'float32[]': (85, '<{}f'),
33  'float64[]': (86, '<{}d'),
34 }
35 
36 
38  """Extract a dictionary of CBOR-friendly values from a ROS message.
39 
40  Primitive values will be casted to specific Python primitives.
41 
42  Typed arrays will be tagged and packed into byte arrays.
43  """
44  out = {}
45  for slot, slot_type in zip(msg.__slots__, msg._slot_types):
46  val = getattr(msg, slot)
47 
48  if PYTHON2:
49  slot = unicode(slot) # noqa: F821
50 
51  # string
52  if slot_type in STRING_TYPES:
53  out[slot] = unicode(val) if PYTHON2 else str(val) # noqa: F821
54 
55  # bool
56  elif slot_type in BOOL_TYPES:
57  out[slot] = bool(val)
58 
59  # integers
60  elif slot_type in INT_TYPES:
61  out[slot] = int(val)
62 
63  # floats
64  elif slot_type in FLOAT_TYPES:
65  out[slot] = float(val)
66 
67  # time/duration
68  elif slot_type in TIME_TYPES:
69  out[slot] = {
70  'secs': int(val.secs),
71  'nsecs': int(val.nsecs),
72  }
73 
74  # byte array
75  elif slot_type in BYTESTREAM_TYPES:
76  if PYTHON2:
77  out[slot] = bytes(bytearray(val))
78  else:
79  out[slot] = bytes(val)
80 
81  # bool array
82  elif slot_type in BOOL_ARRAY_TYPES:
83  out[slot] = [bool(i) for i in val]
84 
85  # numeric arrays
86  elif slot_type in TAGGED_ARRAY_FORMATS:
87  tag, fmt = TAGGED_ARRAY_FORMATS[slot_type]
88  fmt_to_length = fmt.format(len(val))
89  packed = struct.pack(fmt_to_length, *val)
90  out[slot] = Tag(tag=tag, value=packed)
91 
92  # array of messages
93  elif type(val) in LIST_TYPES:
94  out[slot] = [extract_cbor_values(i) for i in val]
95 
96  # message
97  else:
98  out[slot] = extract_cbor_values(val)
99 
100  return out
rosbridge_library.util.cbor.Tag
Definition: cbor.py:256
rosbridge_library.internal.cbor_conversion.extract_cbor_values
def extract_cbor_values(msg)
Definition: cbor_conversion.py:37
rosbridge_library.util.cbor
Definition: cbor.py:1


rosbridge_library
Author(s): Jonathan Mace
autogenerated on Tue Oct 3 2023 02:12:45