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 from __future__ import print_function
00035 import roslib
00036 import rospy
00037 
00038 from rosbridge_library.internal import ros_loader
00039 
00040 import math
00041 import re
00042 import string
00043 from base64 import standard_b64encode, standard_b64decode
00044 
00045 from rosbridge_library.util import string_types, bson
00046 
00047 import sys
00048 if sys.version_info >= (3, 0):
00049     type_map = {
00050     "bool":    ["bool"],
00051     "int":     ["int8", "byte", "uint8", "char",
00052                 "int16", "uint16", "int32", "uint32",
00053                 "int64", "uint64", "float32", "float64"],
00054     "float":   ["float32", "float64"],
00055     "str":     ["string"]
00056     }
00057     primitive_types = [bool, int, float]
00058     python2 = False
00059 else:
00060     type_map = {
00061     "bool":    ["bool"],
00062     "int":     ["int8", "byte", "uint8", "char",
00063                 "int16", "uint16", "int32", "uint32",
00064                 "int64", "uint64", "float32", "float64"],
00065     "float":   ["float32", "float64"],
00066     "str":     ["string"],
00067     "unicode": ["string"],
00068     "long":    ["int64", "uint64"]
00069     }
00070     primitive_types = [bool, int, long, float]
00071     python2 = True
00072 
00073 list_types = [list, tuple]
00074 ros_time_types = ["time", "duration"]
00075 ros_primitive_types = ["bool", "byte", "char", "int8", "uint8", "int16",
00076                        "uint16", "int32", "uint32", "int64", "uint64",
00077                        "float32", "float64", "string"]
00078 ros_header_types = ["Header", "std_msgs/Header", "roslib/Header"]
00079 ros_binary_types = ["uint8[]", "char[]"]
00080 list_braces = re.compile(r'\[[^\]]*\]')
00081 ros_binary_types_list_braces = [("uint8[]", re.compile(r'uint8\[[^\]]*\]')),
00082                                 ("char[]", re.compile(r'char\[[^\]]*\]'))]
00083 
00084 binary_encoder = None
00085 
00086 def get_encoder():
00087     global binary_encoder
00088     if binary_encoder is None:
00089         binary_encoder_type = rospy.get_param('~binary_encoder', 'default')
00090         bson_only_mode = rospy.get_param('~bson_only_mode', False)
00091 
00092         if binary_encoder_type == 'bson' or bson_only_mode:
00093             binary_encoder = bson.Binary
00094         elif binary_encoder_type == 'default' or binary_encoder_type == 'b64':
00095              binary_encoder = standard_b64encode
00096         else:
00097             print("Unknown encoder type '%s'"%binary_encoder_type)
00098             exit(0)
00099     return binary_encoder
00100 
00101 class InvalidMessageException(Exception):
00102     def __init__(self, inst):
00103         Exception.__init__(self, "Unable to extract message values from %s instance" % type(inst).__name__)
00104 
00105 
00106 class NonexistentFieldException(Exception):
00107     def __init__(self, basetype, fields):
00108         Exception.__init__(self, "Message type %s does not have a field %s" % (basetype, '.'.join(fields)))
00109 
00110 
00111 class FieldTypeMismatchException(Exception):
00112     def __init__(self, roottype, fields, expected_type, found_type):
00113         if roottype == expected_type:
00114             Exception.__init__(self, "Expected a JSON object for type %s but received a %s" % (roottype, found_type))
00115         else:
00116             Exception.__init__(self, "%s message requires a %s for field %s, but got a %s" % (roottype, expected_type, '.'.join(fields), found_type))
00117 
00118 
00119 def extract_values(inst):
00120     rostype = getattr(inst, "_type", None)
00121     if rostype is None:
00122         raise InvalidMessageException()
00123     return _from_inst(inst, rostype)
00124 
00125 
00126 def populate_instance(msg, inst):
00127     """ Returns an instance of the provided class, with its fields populated
00128     according to the values in msg """
00129     return _to_inst(msg, inst._type, inst._type, inst)
00130 
00131 
00132 def _from_inst(inst, rostype):
00133     # Special case for uint8[], we encode the string
00134     for binary_type, expression in ros_binary_types_list_braces:
00135         if expression.sub(binary_type, rostype) in ros_binary_types:
00136             encoded = get_encoder()(inst)
00137             return encoded if python2 else encoded.decode('ascii')
00138 
00139     # Check for time or duration
00140     if rostype in ros_time_types:
00141         return {"secs": inst.secs, "nsecs": inst.nsecs}
00142 
00143     # Check for primitive types
00144     if rostype in ros_primitive_types:
00145         #JSON does not support Inf and NaN. They are mapped to None and encoded as null.
00146         if rostype in ["float32", "float64"]:
00147             if math.isnan(inst) or math.isinf(inst):
00148                 return None
00149         return inst
00150 
00151     # Check if it's a list or tuple
00152     if type(inst) in list_types:
00153         return _from_list_inst(inst, rostype)
00154 
00155     # Assume it's otherwise a full ros msg object
00156     return _from_object_inst(inst, rostype)
00157 
00158 
00159 def _from_list_inst(inst, rostype):
00160     # Can duck out early if the list is empty
00161     if len(inst) == 0:
00162         return []
00163 
00164     # Remove the list indicators from the rostype
00165     rostype = list_braces.sub("", rostype)
00166 
00167     # Shortcut for primitives
00168     if rostype in ros_primitive_types and not rostype in ["float32", "float64"]:
00169         return list(inst)
00170 
00171     # Call to _to_inst for every element of the list
00172     return [_from_inst(x, rostype) for x in inst]
00173 
00174 
00175 def _from_object_inst(inst, rostype):
00176     # Create an empty dict then populate with values from the inst
00177     msg = {}
00178     for field_name, field_rostype in zip(inst.__slots__, inst._slot_types):
00179         field_inst = getattr(inst, field_name)
00180         msg[field_name] = _from_inst(field_inst, field_rostype)
00181     return msg
00182 
00183 
00184 def _to_inst(msg, rostype, roottype, inst=None, stack=[]):
00185     # Check if it's uint8[], and if it's a string, try to b64decode
00186     for binary_type, expression in ros_binary_types_list_braces:
00187         if expression.sub(binary_type, rostype) in ros_binary_types:
00188             return _to_binary_inst(msg)
00189 
00190     # Check the type for time or rostime
00191     if rostype in ros_time_types:
00192         return _to_time_inst(msg, rostype, inst)
00193 
00194     # Check to see whether this is a primitive type
00195     if rostype in ros_primitive_types:
00196         return _to_primitive_inst(msg, rostype, roottype, stack)
00197 
00198     # Check whether we're dealing with a list type
00199     if inst is not None and type(inst) in list_types:
00200         return _to_list_inst(msg, rostype, roottype, inst, stack)
00201 
00202     # Otherwise, the type has to be a full ros msg type, so msg must be a dict
00203     if inst is None:
00204         inst = ros_loader.get_message_instance(rostype)
00205 
00206     return _to_object_inst(msg, rostype, roottype, inst, stack)
00207 
00208 
00209 def _to_binary_inst(msg):
00210     if type(msg) in string_types:
00211         try:
00212             return standard_b64decode(msg)
00213         except :
00214             return msg
00215     else:
00216         try:
00217             return bytes(bytearray(msg))
00218         except:
00219             return msg
00220 
00221 
00222 def _to_time_inst(msg, rostype, inst=None):
00223     # Create an instance if we haven't been provided with one
00224     if rostype == "time" and msg == "now":
00225         return rospy.get_rostime()
00226 
00227     if inst is None:
00228         if rostype == "time":
00229             inst = rospy.rostime.Time()
00230         elif rostype == "duration":
00231             inst = rospy.rostime.Duration()
00232         else:
00233             return None
00234 
00235     # Copy across the fields
00236     for field in ["secs", "nsecs"]:
00237         try:
00238             if field in msg:
00239                 setattr(inst, field, msg[field])
00240         except TypeError:
00241             continue
00242 
00243     return inst
00244 
00245 
00246 def _to_primitive_inst(msg, rostype, roottype, stack):
00247     # Typecheck the msg
00248     msgtype = type(msg)
00249     if msgtype in primitive_types and rostype in type_map[msgtype.__name__]:
00250         return msg
00251     elif msgtype in string_types and rostype in type_map[msgtype.__name__]:
00252         return msg.encode("utf-8", "ignore") if python2 else msg
00253     raise FieldTypeMismatchException(roottype, stack, rostype, msgtype)
00254 
00255 
00256 def _to_list_inst(msg, rostype, roottype, inst, stack):
00257     # Typecheck the msg
00258     if type(msg) not in list_types:
00259         raise FieldTypeMismatchException(roottype, stack, rostype, type(msg))
00260 
00261     # Can duck out early if the list is empty
00262     if len(msg) == 0:
00263         return []
00264 
00265     # Remove the list indicators from the rostype
00266     rostype = list_braces.sub("", rostype)
00267 
00268     # Call to _to_inst for every element of the list
00269     return [_to_inst(x, rostype, roottype, None, stack) for x in msg]
00270 
00271 
00272 def _to_object_inst(msg, rostype, roottype, inst, stack):
00273     # Typecheck the msg
00274     if type(msg) is not dict:
00275         raise FieldTypeMismatchException(roottype, stack, rostype, type(msg))
00276 
00277     # Substitute the correct time if we're an std_msgs/Header
00278     if rostype in ros_header_types:
00279         inst.stamp = rospy.get_rostime()
00280 
00281     inst_fields = dict(zip(inst.__slots__, inst._slot_types))
00282 
00283     for field_name in msg:
00284         # Add this field to the field stack
00285         field_stack = stack + [field_name]
00286 
00287         # Raise an exception if the msg contains a bad field
00288         if not field_name in inst_fields:
00289             raise NonexistentFieldException(roottype, field_stack)
00290 
00291         field_rostype = inst_fields[field_name]
00292         field_inst = getattr(inst, field_name)
00293 
00294         field_value = _to_inst(msg[field_name], field_rostype,
00295                     roottype, field_inst, field_stack)
00296 
00297         setattr(inst, field_name, field_value)
00298 
00299     return inst


rosbridge_library
Author(s): Jonathan Mace
autogenerated on Thu Jun 6 2019 21:51:43