message_conversion.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # Software License Agreement (BSD License)
3 #
4 # Copyright (c) 2012, 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 from __future__ import print_function
35 import roslib
36 import rospy
37 
38 from rosbridge_library.internal import ros_loader
39 
40 import math
41 import re
42 import string
43 from base64 import standard_b64encode, standard_b64decode
44 
45 from rosbridge_library.util import string_types, bson
46 
47 import sys
48 if sys.version_info >= (3, 0):
49  type_map = {
50  "bool": ["bool"],
51  "int": ["int8", "byte", "uint8", "char",
52  "int16", "uint16", "int32", "uint32",
53  "int64", "uint64", "float32", "float64"],
54  "float": ["float32", "float64"],
55  "str": ["string"]
56  }
57  primitive_types = [bool, int, float]
58  python2 = False
59 else:
60  type_map = {
61  "bool": ["bool"],
62  "int": ["int8", "byte", "uint8", "char",
63  "int16", "uint16", "int32", "uint32",
64  "int64", "uint64", "float32", "float64"],
65  "float": ["float32", "float64"],
66  "str": ["string"],
67  "unicode": ["string"],
68  "long": ["int64", "uint64"]
69  }
70  primitive_types = [bool, int, long, float]
71  python2 = True
72 
73 list_types = [list, tuple]
74 ros_time_types = ["time", "duration"]
75 ros_primitive_types = ["bool", "byte", "char", "int8", "uint8", "int16",
76  "uint16", "int32", "uint32", "int64", "uint64",
77  "float32", "float64", "string"]
78 ros_header_types = ["Header", "std_msgs/Header", "roslib/Header"]
79 ros_binary_types = ["uint8[]", "char[]"]
80 list_braces = re.compile(r'\[[^\]]*\]')
81 ros_binary_types_list_braces = [("uint8[]", re.compile(r'uint8\[[^\]]*\]')),
82  ("char[]", re.compile(r'char\[[^\]]*\]'))]
83 
84 binary_encoder = None
85 bson_only_mode = None
86 
88  global binary_encoder,bson_only_mode
89  if binary_encoder is None:
90  binary_encoder_type = rospy.get_param('~binary_encoder', 'default')
91  bson_only_mode = rospy.get_param('~bson_only_mode', False)
92 
93  if binary_encoder_type == 'bson' or bson_only_mode:
94  binary_encoder = bson.Binary
95  elif binary_encoder_type == 'default' or binary_encoder_type == 'b64':
96  binary_encoder = standard_b64encode
97  else:
98  print("Unknown encoder type '%s'"%binary_encoder_type)
99  exit(0)
100  return binary_encoder
101 
102 class InvalidMessageException(Exception):
103  def __init__(self, inst):
104  Exception.__init__(self, "Unable to extract message values from %s instance" % type(inst).__name__)
105 
106 
107 class NonexistentFieldException(Exception):
108  def __init__(self, basetype, fields):
109  Exception.__init__(self, "Message type %s does not have a field %s" % (basetype, '.'.join(fields)))
110 
111 
112 class FieldTypeMismatchException(Exception):
113  def __init__(self, roottype, fields, expected_type, found_type):
114  if roottype == expected_type:
115  Exception.__init__(self, "Expected a JSON object for type %s but received a %s" % (roottype, found_type))
116  else:
117  Exception.__init__(self, "%s message requires a %s for field %s, but got a %s" % (roottype, expected_type, '.'.join(fields), found_type))
118 
119 
120 def extract_values(inst):
121  rostype = getattr(inst, "_type", None)
122  if rostype is None:
123  raise InvalidMessageException(inst=inst)
124  return _from_inst(inst, rostype)
125 
126 
127 def populate_instance(msg, inst):
128  """ Returns an instance of the provided class, with its fields populated
129  according to the values in msg """
130  return _to_inst(msg, inst._type, inst._type, inst)
131 
132 
133 def _from_inst(inst, rostype):
134  global bson_only_mode
135  # Special case for uint8[], we encode the string
136  for binary_type, expression in ros_binary_types_list_braces:
137  if expression.sub(binary_type, rostype) in ros_binary_types:
138  encoded = get_encoder()(inst)
139  return encoded if python2 else encoded.decode('ascii')
140 
141  # Check for time or duration
142  if rostype in ros_time_types:
143  return {"secs": inst.secs, "nsecs": inst.nsecs}
144 
145  if(bson_only_mode is None):bson_only_mode = rospy.get_param('~bson_only_mode', False)
146  # Check for primitive types
147  if rostype in ros_primitive_types:
148  #JSON does not support Inf and NaN. They are mapped to None and encoded as null
149  if (not bson_only_mode) and (rostype in ["float32", "float64"]):
150  if math.isnan(inst) or math.isinf(inst):
151  return None
152  return inst
153 
154  # Check if it's a list or tuple
155  if type(inst) in list_types:
156  return _from_list_inst(inst, rostype)
157 
158  # Assume it's otherwise a full ros msg object
159  return _from_object_inst(inst, rostype)
160 
161 
162 def _from_list_inst(inst, rostype):
163  # Can duck out early if the list is empty
164  if len(inst) == 0:
165  return []
166 
167  # Remove the list indicators from the rostype
168  rostype = list_braces.sub("", rostype)
169 
170  # Shortcut for primitives
171  if rostype in ros_primitive_types and not rostype in ["float32", "float64"]:
172  return list(inst)
173 
174  # Call to _to_inst for every element of the list
175  return [_from_inst(x, rostype) for x in inst]
176 
177 
178 def _from_object_inst(inst, rostype):
179  # Create an empty dict then populate with values from the inst
180  msg = {}
181  for field_name, field_rostype in zip(inst.__slots__, inst._slot_types):
182  field_inst = getattr(inst, field_name)
183  msg[field_name] = _from_inst(field_inst, field_rostype)
184  return msg
185 
186 
187 def _to_inst(msg, rostype, roottype, inst=None, stack=[]):
188  # Check if it's uint8[], and if it's a string, try to b64decode
189  for binary_type, expression in ros_binary_types_list_braces:
190  if expression.sub(binary_type, rostype) in ros_binary_types:
191  return _to_binary_inst(msg)
192 
193  # Check the type for time or rostime
194  if rostype in ros_time_types:
195  return _to_time_inst(msg, rostype, inst)
196 
197  # Check to see whether this is a primitive type
198  if rostype in ros_primitive_types:
199  return _to_primitive_inst(msg, rostype, roottype, stack)
200 
201  # Check whether we're dealing with a list type
202  if inst is not None and type(inst) in list_types:
203  return _to_list_inst(msg, rostype, roottype, inst, stack)
204 
205  # Otherwise, the type has to be a full ros msg type, so msg must be a dict
206  if inst is None:
207  inst = ros_loader.get_message_instance(rostype)
208 
209  return _to_object_inst(msg, rostype, roottype, inst, stack)
210 
211 
213  if type(msg) in string_types:
214  try:
215  return standard_b64decode(msg)
216  except :
217  return msg
218  else:
219  try:
220  return bytes(bytearray(msg))
221  except:
222  return msg
223 
224 
225 def _to_time_inst(msg, rostype, inst=None):
226  # Create an instance if we haven't been provided with one
227  if rostype == "time" and msg == "now":
228  return rospy.get_rostime()
229 
230  if inst is None:
231  if rostype == "time":
232  inst = rospy.rostime.Time()
233  elif rostype == "duration":
234  inst = rospy.rostime.Duration()
235  else:
236  return None
237 
238  # Copy across the fields
239  for field in ["secs", "nsecs"]:
240  try:
241  if field in msg:
242  setattr(inst, field, msg[field])
243  except TypeError:
244  continue
245 
246  return inst
247 
248 
249 def _to_primitive_inst(msg, rostype, roottype, stack):
250  # Typecheck the msg
251  msgtype = type(msg)
252  if msgtype in primitive_types and rostype in type_map[msgtype.__name__]:
253  return msg
254  elif msgtype in string_types and rostype in type_map[msgtype.__name__]:
255  return msg.encode("utf-8", "ignore") if python2 else msg
256  raise FieldTypeMismatchException(roottype, stack, rostype, msgtype)
257 
258 
259 def _to_list_inst(msg, rostype, roottype, inst, stack):
260  # Typecheck the msg
261  if type(msg) not in list_types:
262  raise FieldTypeMismatchException(roottype, stack, rostype, type(msg))
263 
264  # Can duck out early if the list is empty
265  if len(msg) == 0:
266  return []
267 
268  # Remove the list indicators from the rostype
269  rostype = list_braces.sub("", rostype)
270 
271  # Call to _to_inst for every element of the list
272  return [_to_inst(x, rostype, roottype, None, stack) for x in msg]
273 
274 
275 def _to_object_inst(msg, rostype, roottype, inst, stack):
276  # Typecheck the msg
277  if type(msg) is not dict:
278  raise FieldTypeMismatchException(roottype, stack, rostype, type(msg))
279 
280  # Substitute the correct time if we're an std_msgs/Header
281  try:
282  if rostype in ros_header_types:
283  inst.stamp = rospy.get_rostime()
284  except rospy.exceptions.ROSInitException as e:
285  rospy.logdebug("Not substituting the correct header time: %s" % e)
286 
287  inst_fields = dict(zip(inst.__slots__, inst._slot_types))
288 
289  for field_name in msg:
290  # Add this field to the field stack
291  field_stack = stack + [field_name]
292 
293  # Raise an exception if the msg contains a bad field
294  if not field_name in inst_fields:
295  raise NonexistentFieldException(roottype, field_stack)
296 
297  field_rostype = inst_fields[field_name]
298  field_inst = getattr(inst, field_name)
299 
300  field_value = _to_inst(msg[field_name], field_rostype,
301  roottype, field_inst, field_stack)
302 
303  setattr(inst, field_name, field_value)
304 
305  return inst
def _to_object_inst(msg, rostype, roottype, inst, stack)
def __init__(self, roottype, fields, expected_type, found_type)
def _to_list_inst(msg, rostype, roottype, inst, stack)
def _to_primitive_inst(msg, rostype, roottype, stack)
def _to_inst(msg, rostype, roottype, inst=None, stack=[])


rosbridge_library
Author(s): Jonathan Mace
autogenerated on Fri May 10 2019 02:17:02