00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034 import roslib
00035 import rospy
00036
00037 from rosbridge_library.internal import ros_loader
00038
00039 import math
00040 import re
00041 import string
00042 from base64 import standard_b64encode, standard_b64decode
00043 import bson
00044
00045 type_map = {
00046 "bool": ["bool"],
00047 "int": ["int8", "byte", "uint8", "char",
00048 "int16", "uint16", "int32", "uint32",
00049 "int64", "uint64", "float32", "float64"],
00050 "float": ["float32", "float64"],
00051 "str": ["string"],
00052 "unicode": ["string"],
00053 "long": ["uint64"]
00054 }
00055 primitive_types = [bool, int, long, float]
00056 string_types = [str, unicode]
00057 list_types = [list, tuple]
00058 ros_time_types = ["time", "duration"]
00059 ros_primitive_types = ["bool", "byte", "char", "int8", "uint8", "int16",
00060 "uint16", "int32", "uint32", "int64", "uint64",
00061 "float32", "float64", "string"]
00062 ros_header_types = ["Header", "std_msgs/Header", "roslib/Header"]
00063 ros_binary_types = ["uint8[]", "char[]"]
00064 list_braces = re.compile(r'\[[^\]]*\]')
00065 ros_binary_types_list_braces = [("uint8[]", re.compile(r'uint8\[[^\]]*\]')),
00066 ("char[]", re.compile(r'char\[[^\]]*\]'))]
00067
00068 binary_encoder = None
00069
00070 def get_encoder():
00071 global binary_encoder
00072 if binary_encoder is None:
00073 binary_encoder_type = rospy.get_param('~binary_encoder', 'b64')
00074 if binary_encoder_type == 'b64':
00075 binary_encoder = standard_b64encode
00076 elif binary_encoder_type == 'bson':
00077 binary_encoder = bson.Binary
00078 else:
00079 print "Unknown encoder type '%s'"%binary_encoder_type
00080 exit(0)
00081 return binary_encoder
00082
00083 class InvalidMessageException(Exception):
00084 def __init__(self, inst):
00085 Exception.__init__(self, "Unable to extract message values from %s instance" % type(inst).__name__)
00086
00087
00088 class NonexistentFieldException(Exception):
00089 def __init__(self, basetype, fields):
00090 Exception.__init__(self, "Message type %s does not have a field %s" % (basetype, '.'.join(fields)))
00091
00092
00093 class FieldTypeMismatchException(Exception):
00094 def __init__(self, roottype, fields, expected_type, found_type):
00095 if roottype == expected_type:
00096 Exception.__init__(self, "Expected a JSON object for type %s but received a %s" % (roottype, found_type))
00097 else:
00098 Exception.__init__(self, "%s message requires a %s for field %s, but got a %s" % (roottype, expected_type, '.'.join(fields), found_type))
00099
00100
00101 def extract_values(inst):
00102 rostype = getattr(inst, "_type", None)
00103 if rostype is None:
00104 raise InvalidMessageException()
00105 return _from_inst(inst, rostype)
00106
00107
00108 def populate_instance(msg, inst):
00109 """ Returns an instance of the provided class, with its fields populated
00110 according to the values in msg """
00111 return _to_inst(msg, inst._type, inst._type, inst)
00112
00113
00114 def _from_inst(inst, rostype):
00115
00116 for binary_type, expression in ros_binary_types_list_braces:
00117 if expression.sub(binary_type, rostype) in ros_binary_types:
00118 return get_encoder()(inst)
00119
00120
00121 if rostype in ros_time_types:
00122 return {"secs": inst.secs, "nsecs": inst.nsecs}
00123
00124
00125 if rostype in ros_primitive_types:
00126
00127 if rostype in ["float32", "float64"]:
00128 if math.isnan(inst) or math.isinf(inst):
00129 return None
00130 return inst
00131
00132
00133 if type(inst) in list_types:
00134 return _from_list_inst(inst, rostype)
00135
00136
00137 return _from_object_inst(inst, rostype)
00138
00139
00140 def _from_list_inst(inst, rostype):
00141
00142 if len(inst) == 0:
00143 return []
00144
00145
00146 rostype = list_braces.sub("", rostype)
00147
00148
00149 if rostype in ros_primitive_types and not rostype in ["float32", "float64"]:
00150 return list(inst)
00151
00152
00153 return [_from_inst(x, rostype) for x in inst]
00154
00155
00156 def _from_object_inst(inst, rostype):
00157
00158 msg = {}
00159 for field_name, field_rostype in zip(inst.__slots__, inst._slot_types):
00160 field_inst = getattr(inst, field_name)
00161 msg[field_name] = _from_inst(field_inst, field_rostype)
00162 return msg
00163
00164
00165 def _to_inst(msg, rostype, roottype, inst=None, stack=[]):
00166
00167 for binary_type, expression in ros_binary_types_list_braces:
00168 if expression.sub(binary_type, rostype) in ros_binary_types:
00169 return _to_binary_inst(msg)
00170
00171
00172 if rostype in ros_time_types:
00173 return _to_time_inst(msg, rostype, inst)
00174
00175
00176 if rostype in ros_primitive_types:
00177 return _to_primitive_inst(msg, rostype, roottype, stack)
00178
00179
00180 if inst is not None and type(inst) in list_types:
00181 return _to_list_inst(msg, rostype, roottype, inst, stack)
00182
00183
00184 if inst is None:
00185 inst = ros_loader.get_message_instance(rostype)
00186
00187 return _to_object_inst(msg, rostype, roottype, inst, stack)
00188
00189
00190 def _to_binary_inst(msg):
00191 if type(msg) in string_types:
00192 try:
00193 return standard_b64decode(msg)
00194 except:
00195 return msg
00196 else:
00197 try:
00198 return str(bytearray(msg))
00199 except:
00200 return msg
00201
00202
00203 def _to_time_inst(msg, rostype, inst=None):
00204
00205 if rostype == "time" and msg == "now":
00206 return rospy.get_rostime()
00207
00208 if inst is None:
00209 if rostype == "time":
00210 inst = rospy.rostime.Time()
00211 elif rostype == "duration":
00212 inst = rospy.rostime.Duration()
00213 else:
00214 return None
00215
00216
00217 for field in ["secs", "nsecs"]:
00218 try:
00219 if field in msg:
00220 setattr(inst, field, msg[field])
00221 except TypeError:
00222 continue
00223
00224 return inst
00225
00226
00227 def _to_primitive_inst(msg, rostype, roottype, stack):
00228
00229 msgtype = type(msg)
00230 if msgtype in primitive_types and rostype in type_map[msgtype.__name__]:
00231 return msg
00232 elif msgtype in string_types and rostype in type_map[msgtype.__name__]:
00233 return msg.encode("utf-8", "ignore")
00234 raise FieldTypeMismatchException(roottype, stack, rostype, msgtype)
00235
00236
00237 def _to_list_inst(msg, rostype, roottype, inst, stack):
00238
00239 if type(msg) not in list_types:
00240 raise FieldTypeMismatchException(roottype, stack, rostype, type(msg))
00241
00242
00243 if len(msg) == 0:
00244 return []
00245
00246
00247 rostype = list_braces.sub("", rostype)
00248
00249
00250 return [_to_inst(x, rostype, roottype, None, stack) for x in msg]
00251
00252
00253 def _to_object_inst(msg, rostype, roottype, inst, stack):
00254
00255 if type(msg) is not dict:
00256 raise FieldTypeMismatchException(roottype, stack, rostype, type(msg))
00257
00258
00259 if rostype in ros_header_types:
00260 inst.stamp = rospy.get_rostime()
00261
00262 inst_fields = dict(zip(inst.__slots__, inst._slot_types))
00263
00264 for field_name in msg:
00265
00266 field_stack = stack + [field_name]
00267
00268
00269 if not field_name in inst_fields:
00270 raise NonexistentFieldException(roottype, field_stack)
00271
00272 field_rostype = inst_fields[field_name]
00273 field_inst = getattr(inst, field_name)
00274
00275 field_value = _to_inst(msg[field_name], field_rostype,
00276 roottype, field_inst, field_stack)
00277
00278 setattr(inst, field_name, field_value)
00279
00280 return inst