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 re
00040 import string
00041 from base64 import standard_b64encode, standard_b64decode
00042 
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 
00065 
00066 class InvalidMessageException(Exception):
00067     def __init__(self, inst):
00068         Exception.__init__(self, "Unable to extract message values from %s instance" % type(inst).__name__)
00069 
00070 
00071 class NonexistentFieldException(Exception):
00072     def __init__(self, basetype, fields):
00073         Exception.__init__(self, "Message type %s does not have a field %s" % (basetype, '.'.join(fields)))
00074 
00075 
00076 class FieldTypeMismatchException(Exception):
00077     def __init__(self, roottype, fields, expected_type, found_type):
00078         if roottype == expected_type:
00079             Exception.__init__(self, "Expected a JSON object for type %s but received a %s" % (roottype, found_type))
00080         else:
00081             Exception.__init__(self, "%s message requires a %s for field %s, but got a %s" % (roottype, expected_type, '.'.join(fields), found_type))
00082 
00083 
00084 def extract_values(inst):
00085     rostype = getattr(inst, "_type", None)
00086     if rostype is None:
00087         raise InvalidMessageException()
00088     return _from_inst(inst, rostype)
00089 
00090 
00091 def populate_instance(msg, inst):
00092     """ Returns an instance of the provided class, with its fields populated
00093     according to the values in msg """
00094     return _to_inst(msg, inst._type, inst._type, inst)
00095 
00096 
00097 def _from_inst(inst, rostype):
00098     # Special case for uint8[], we base64 encode the string
00099     if rostype in ros_binary_types:
00100         return standard_b64encode(inst)
00101 
00102     # Check for time or duration
00103     if rostype in ros_time_types:
00104         return {"secs": inst.secs, "nsecs": inst.nsecs}
00105 
00106     # Check for primitive types
00107     if rostype in ros_primitive_types:
00108         return inst
00109 
00110     # Check if it's a list or tuple
00111     if type(inst) in list_types:
00112         return _from_list_inst(inst, rostype)
00113 
00114     # Assume it's otherwise a full ros msg object
00115     return _from_object_inst(inst, rostype)
00116 
00117 
00118 def _from_list_inst(inst, rostype):
00119     # Can duck out early if the list is empty
00120     if len(inst) == 0:
00121         return []
00122 
00123     # Remove the list indicators from the rostype
00124     rostype = list_braces.sub("", rostype)
00125     
00126     # Shortcut for primitives
00127     if rostype in ros_primitive_types:
00128         return list(inst)
00129 
00130     # Call to _to_inst for every element of the list
00131     return [_from_inst(x, rostype) for x in inst]
00132 
00133 
00134 def _from_object_inst(inst, rostype):
00135     # Create an empty dict then populate with values from the inst
00136     msg = {}
00137     for field_name, field_rostype in zip(inst.__slots__, inst._slot_types):
00138         field_inst = getattr(inst, field_name)
00139         msg[field_name] = _from_inst(field_inst, field_rostype)
00140     return msg
00141 
00142 
00143 def _to_inst(msg, rostype, roottype, inst=None, stack=[]):
00144     # Check if it's uint8[], and if it's a string, try to b64decode
00145     if rostype in ros_binary_types:
00146         return _to_binary_inst(msg)
00147 
00148     # Check the type for time or rostime
00149     if rostype in ros_time_types:
00150         return _to_time_inst(msg, rostype, inst)
00151 
00152     # Check to see whether this is a primitive type
00153     if rostype in ros_primitive_types:
00154         return _to_primitive_inst(msg, rostype, roottype, stack)
00155 
00156     # Check whether we're dealing with a list type
00157     if inst is not None and type(inst) in list_types:
00158         return _to_list_inst(msg, rostype, roottype, inst, stack)
00159 
00160     # Otherwise, the type has to be a full ros msg type, so msg must be a dict
00161     if inst is None:
00162         inst = ros_loader.get_message_instance(rostype)
00163 
00164     return _to_object_inst(msg, rostype, roottype, inst, stack)
00165 
00166 
00167 def _to_binary_inst(msg):
00168     if type(msg) in string_types:
00169         try:
00170             return standard_b64decode(msg)
00171         except:
00172             return msg
00173     else:
00174         try:
00175             return str(bytearray(msg))
00176         except:
00177             return msg
00178 
00179 
00180 def _to_time_inst(msg, rostype, inst=None):
00181     # Create an instance if we haven't been provided with one
00182     if rostype == "time" and msg == "now":
00183         return rospy.get_rostime()
00184 
00185     if inst is None:
00186         if rostype == "time":
00187             inst = rospy.rostime.Time()
00188         elif rostype == "duration":
00189             inst = rospy.rostime.Duration()
00190         else:
00191             return None
00192 
00193     # Copy across the fields
00194     for field in ["secs", "nsecs"]:
00195         try:
00196             if field in msg:
00197                 setattr(inst, field, msg[field])
00198         except TypeError:
00199             continue
00200 
00201     return inst
00202 
00203 
00204 def _to_primitive_inst(msg, rostype, roottype, stack):
00205     # Typecheck the msg
00206     msgtype = type(msg)
00207     if msgtype in primitive_types and rostype in type_map[msgtype.__name__]:
00208         return msg
00209     elif msgtype in string_types and rostype in type_map[msgtype.__name__]:
00210         return msg.encode("ascii", "ignore")
00211     raise FieldTypeMismatchException(roottype, stack, rostype, msgtype)
00212 
00213 
00214 def _to_list_inst(msg, rostype, roottype, inst, stack):
00215     # Typecheck the msg
00216     if type(msg) not in list_types:
00217         raise FieldTypeMismatchException(roottype, stack, rostype, type(msg))
00218 
00219     # Can duck out early if the list is empty
00220     if len(msg) == 0:
00221         return []
00222 
00223     # Remove the list indicators from the rostype
00224     rostype = list_braces.sub("", rostype)
00225 
00226     # Call to _to_inst for every element of the list
00227     return [_to_inst(x, rostype, roottype, None, stack) for x in msg]
00228 
00229 
00230 def _to_object_inst(msg, rostype, roottype, inst, stack):
00231     # Typecheck the msg
00232     if type(msg) is not dict:
00233         raise FieldTypeMismatchException(roottype, stack, rostype, type(msg))
00234 
00235     # Substitute the correct time if we're an std_msgs/Header
00236     if rostype in ros_header_types:
00237         inst.stamp = rospy.get_rostime()
00238 
00239     inst_fields = dict(zip(inst.__slots__, inst._slot_types))
00240 
00241     for field_name in msg:
00242         # Add this field to the field stack
00243         field_stack = stack + [field_name]
00244 
00245         # Raise an exception if the msg contains a bad field
00246         if not field_name in inst_fields:
00247             raise NonexistentFieldException(roottype, field_stack)
00248 
00249         field_rostype = inst_fields[field_name]
00250         field_inst = getattr(inst, field_name)
00251 
00252         field_value = _to_inst(msg[field_name], field_rostype,
00253                     roottype, field_inst, field_stack)
00254 
00255         setattr(inst, field_name, field_value)
00256 
00257     return inst


rosbridge_library
Author(s): Jonathan Mace
autogenerated on Thu Jan 2 2014 11:53:35