message_conversion.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # Software License Agreement (BSD License)
00003 #
00004 # Copyright (c) 2012, Willow Garage, Inc.
00005 # All rights reserved.
00006 #
00007 # Redistribution and use in source and binary forms, with or without
00008 # modification, are permitted provided that the following conditions
00009 # are met:
00010 #
00011 #  * Redistributions of source code must retain the above copyright
00012 #    notice, this list of conditions and the following disclaimer.
00013 #  * Redistributions in binary form must reproduce the above
00014 #    copyright notice, this list of conditions and the following
00015 #    disclaimer in the documentation and/or other materials provided
00016 #    with the distribution.
00017 #  * Neither the name of Willow Garage, Inc. nor the names of its
00018 #    contributors may be used to endorse or promote products derived
00019 #    from this software without specific prior written permission.
00020 #
00021 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 # POSSIBILITY OF SUCH DAMAGE.
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":    ["int64", "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', 'default')
00074         bson_only_mode = rospy.get_param('~bson_only_mode', False)
00075 
00076         if binary_encoder_type == 'bson' or bson_only_mode:
00077             binary_encoder = bson.Binary
00078         elif binary_encoder_type == 'default' or binary_encoder_type == 'b64':
00079              binary_encoder = standard_b64encode
00080         else:
00081             print "Unknown encoder type '%s'"%binary_encoder_type
00082             exit(0)
00083     return binary_encoder        
00084 
00085 class InvalidMessageException(Exception):
00086     def __init__(self, inst):
00087         Exception.__init__(self, "Unable to extract message values from %s instance" % type(inst).__name__)
00088 
00089 
00090 class NonexistentFieldException(Exception):
00091     def __init__(self, basetype, fields):
00092         Exception.__init__(self, "Message type %s does not have a field %s" % (basetype, '.'.join(fields)))
00093 
00094 
00095 class FieldTypeMismatchException(Exception):
00096     def __init__(self, roottype, fields, expected_type, found_type):
00097         if roottype == expected_type:
00098             Exception.__init__(self, "Expected a JSON object for type %s but received a %s" % (roottype, found_type))
00099         else:
00100             Exception.__init__(self, "%s message requires a %s for field %s, but got a %s" % (roottype, expected_type, '.'.join(fields), found_type))
00101 
00102 
00103 def extract_values(inst):
00104     rostype = getattr(inst, "_type", None)
00105     if rostype is None:
00106         raise InvalidMessageException()
00107     return _from_inst(inst, rostype)
00108 
00109 
00110 def populate_instance(msg, inst):
00111     """ Returns an instance of the provided class, with its fields populated
00112     according to the values in msg """
00113     return _to_inst(msg, inst._type, inst._type, inst)
00114 
00115 
00116 def _from_inst(inst, rostype):
00117     # Special case for uint8[], we encode the string
00118     for binary_type, expression in ros_binary_types_list_braces:
00119         if expression.sub(binary_type, rostype) in ros_binary_types:
00120             return get_encoder()(inst)
00121 
00122     # Check for time or duration
00123     if rostype in ros_time_types:
00124         return {"secs": inst.secs, "nsecs": inst.nsecs}
00125 
00126     # Check for primitive types
00127     if rostype in ros_primitive_types:
00128         #JSON does not support Inf and NaN. They are mapped to None and encoded as null.
00129         if rostype in ["float32", "float64"]:
00130             if math.isnan(inst) or math.isinf(inst):
00131                 return None
00132         return inst
00133 
00134     # Check if it's a list or tuple
00135     if type(inst) in list_types:
00136         return _from_list_inst(inst, rostype)
00137 
00138     # Assume it's otherwise a full ros msg object
00139     return _from_object_inst(inst, rostype)
00140 
00141 
00142 def _from_list_inst(inst, rostype):
00143     # Can duck out early if the list is empty
00144     if len(inst) == 0:
00145         return []
00146 
00147     # Remove the list indicators from the rostype
00148     rostype = list_braces.sub("", rostype)
00149 
00150     # Shortcut for primitives
00151     if rostype in ros_primitive_types and not rostype in ["float32", "float64"]:
00152         return list(inst)
00153 
00154     # Call to _to_inst for every element of the list
00155     return [_from_inst(x, rostype) for x in inst]
00156 
00157 
00158 def _from_object_inst(inst, rostype):
00159     # Create an empty dict then populate with values from the inst
00160     msg = {}
00161     for field_name, field_rostype in zip(inst.__slots__, inst._slot_types):
00162         field_inst = getattr(inst, field_name)
00163         msg[field_name] = _from_inst(field_inst, field_rostype)
00164     return msg
00165 
00166 
00167 def _to_inst(msg, rostype, roottype, inst=None, stack=[]):
00168     # Check if it's uint8[], and if it's a string, try to b64decode
00169     for binary_type, expression in ros_binary_types_list_braces:
00170         if expression.sub(binary_type, rostype) in ros_binary_types:
00171             return _to_binary_inst(msg)
00172 
00173     # Check the type for time or rostime
00174     if rostype in ros_time_types:
00175         return _to_time_inst(msg, rostype, inst)
00176 
00177     # Check to see whether this is a primitive type
00178     if rostype in ros_primitive_types:
00179         return _to_primitive_inst(msg, rostype, roottype, stack)
00180 
00181     # Check whether we're dealing with a list type
00182     if inst is not None and type(inst) in list_types:
00183         return _to_list_inst(msg, rostype, roottype, inst, stack)
00184 
00185     # Otherwise, the type has to be a full ros msg type, so msg must be a dict
00186     if inst is None:
00187         inst = ros_loader.get_message_instance(rostype)
00188 
00189     return _to_object_inst(msg, rostype, roottype, inst, stack)
00190 
00191 
00192 def _to_binary_inst(msg):
00193     if type(msg) in string_types:
00194         try:
00195             return standard_b64decode(msg)
00196         except:
00197             return msg
00198     else:
00199         try:
00200             return str(bytearray(msg))
00201         except:
00202             return msg
00203 
00204 
00205 def _to_time_inst(msg, rostype, inst=None):
00206     # Create an instance if we haven't been provided with one
00207     if rostype == "time" and msg == "now":
00208         return rospy.get_rostime()
00209 
00210     if inst is None:
00211         if rostype == "time":
00212             inst = rospy.rostime.Time()
00213         elif rostype == "duration":
00214             inst = rospy.rostime.Duration()
00215         else:
00216             return None
00217 
00218     # Copy across the fields
00219     for field in ["secs", "nsecs"]:
00220         try:
00221             if field in msg:
00222                 setattr(inst, field, msg[field])
00223         except TypeError:
00224             continue
00225 
00226     return inst
00227 
00228 
00229 def _to_primitive_inst(msg, rostype, roottype, stack):
00230     # Typecheck the msg
00231     msgtype = type(msg)
00232     if msgtype in primitive_types and rostype in type_map[msgtype.__name__]:
00233         return msg
00234     elif msgtype in string_types and rostype in type_map[msgtype.__name__]:
00235         return msg.encode("utf-8", "ignore")
00236     raise FieldTypeMismatchException(roottype, stack, rostype, msgtype)
00237 
00238 
00239 def _to_list_inst(msg, rostype, roottype, inst, stack):
00240     # Typecheck the msg
00241     if type(msg) not in list_types:
00242         raise FieldTypeMismatchException(roottype, stack, rostype, type(msg))
00243 
00244     # Can duck out early if the list is empty
00245     if len(msg) == 0:
00246         return []
00247 
00248     # Remove the list indicators from the rostype
00249     rostype = list_braces.sub("", rostype)
00250 
00251     # Call to _to_inst for every element of the list
00252     return [_to_inst(x, rostype, roottype, None, stack) for x in msg]
00253 
00254 
00255 def _to_object_inst(msg, rostype, roottype, inst, stack):
00256     # Typecheck the msg
00257     if type(msg) is not dict:
00258         raise FieldTypeMismatchException(roottype, stack, rostype, type(msg))
00259 
00260     # Substitute the correct time if we're an std_msgs/Header
00261     if rostype in ros_header_types:
00262         inst.stamp = rospy.get_rostime()
00263 
00264     inst_fields = dict(zip(inst.__slots__, inst._slot_types))
00265 
00266     for field_name in msg:
00267         # Add this field to the field stack
00268         field_stack = stack + [field_name]
00269 
00270         # Raise an exception if the msg contains a bad field
00271         if not field_name in inst_fields:
00272             raise NonexistentFieldException(roottype, field_stack)
00273 
00274         field_rostype = inst_fields[field_name]
00275         field_inst = getattr(inst, field_name)
00276 
00277         field_value = _to_inst(msg[field_name], field_rostype,
00278                     roottype, field_inst, field_stack)
00279 
00280         setattr(inst, field_name, field_value)
00281 
00282     return inst


rosbridge_library
Author(s): Jonathan Mace
autogenerated on Wed Sep 13 2017 03:18:07