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