message_converter.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # Software License Agreement (BSD License)
00003 #
00004 # Copyright (c) 2013, 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.message
00035 import rospy
00036 import re
00037 import base64
00038 from pprint import pprint
00039 
00040 python_to_ros_type_map = {
00041     'bool'    : ['bool'],
00042     'int'     : ['int8', 'byte', 'uint8', 'char',
00043                  'int16', 'uint16', 'int32', 'uint32',
00044                  'int64', 'uint64', 'float32', 'float64'],
00045     'float'   : ['float32', 'float64'],
00046     'str'     : ['string'],
00047     'unicode' : ['string'],
00048     'long'    : ['uint64']
00049 }
00050 
00051 python_primitive_types = [bool, int, long, float]
00052 python_string_types = [str, unicode]
00053 python_list_types = [list, tuple]
00054 
00055 ros_time_types = ['time', 'duration']
00056 ros_primitive_types = ['bool', 'byte', 'char', 'int8', 'uint8', 'int16',
00057                        'uint16', 'int32', 'uint32', 'int64', 'uint64',
00058                        'float32', 'float64', 'string']
00059 ros_header_types = ['Header', 'std_msgs/Header', 'roslib/Header']
00060 ros_binary_types_regexp = re.compile(r'(uint8|char)\[[^\]]*\]')
00061 
00062 list_brackets = re.compile(r'\[[^\]]*\]')
00063 
00064 def convert_dictionary_to_ros_message(message_type, dictionary):
00065     """
00066     Takes in the message type and a Python dictionary and returns a ROS message.
00067 
00068     Example:
00069         message_type = "std_msgs/String"
00070         dict_message = { "data": "Hello, Robot" }
00071         ros_message = convert_dictionary_to_ros_message(message_type, dict_message)
00072     """
00073     message_class = roslib.message.get_message_class(message_type)
00074     message = message_class()
00075     message_fields = dict(_get_message_fields(message))
00076 
00077     for field_name, field_value in dictionary.items():
00078         if field_name in message_fields:
00079             field_type = message_fields[field_name]
00080             field_value = _convert_to_ros_type(field_type, field_value)
00081             setattr(message, field_name, field_value)
00082         else:
00083             error_message = 'ROS message type "{0}" has no field named "{1}"'\
00084                 .format(message_type, field_name)
00085             raise ValueError(error_message)
00086 
00087     return message
00088 
00089 def _convert_to_ros_type(field_type, field_value):
00090     if is_ros_binary_type(field_type, field_value):
00091         field_value = _convert_to_ros_binary(field_type, field_value)
00092     elif field_type in ros_time_types:
00093         field_value = _convert_to_ros_time(field_type, field_value)
00094     elif field_type in ros_primitive_types:
00095         field_value = _convert_to_ros_primitive(field_type, field_value)
00096     elif _is_field_type_an_array(field_type):
00097         field_value = _convert_to_ros_array(field_type, field_value)
00098     else:
00099         field_value = convert_dictionary_to_ros_message(field_type, field_value)
00100 
00101     return field_value
00102 
00103 def _convert_to_ros_binary(field_type, field_value):
00104     binary_value_as_string = field_value
00105     if type(field_value) in python_string_types:
00106         binary_value_as_string = base64.standard_b64decode(field_value)
00107     else:
00108         binary_value_as_string = str(bytearray(field_value))
00109 
00110     return binary_value_as_string
00111 
00112 def _convert_to_ros_time(field_type, field_value):
00113     time = None
00114 
00115     if field_type == 'time' and field_value == 'now':
00116         time = rospy.get_rostime()
00117     else:
00118         if field_type == 'time':
00119             time = rospy.rostime.Time()
00120         elif field_type == 'duration':
00121             time = rospy.rostime.Duration()
00122         if 'secs' in field_value:
00123             setattr(time, 'secs', field_value['secs'])
00124         if 'nsecs' in field_value:
00125             setattr(time, 'nsecs', field_value['nsecs'])
00126 
00127     return time
00128 
00129 def _convert_to_ros_primitive(field_type, field_value):
00130     return field_value
00131 
00132 def _convert_to_ros_array(field_type, list_value):
00133     list_type = list_brackets.sub('', field_type)
00134     return [_convert_to_ros_type(list_type, value) for value in list_value]
00135 
00136 def convert_ros_message_to_dictionary(message):
00137     """
00138     Takes in a ROS message and returns a Python dictionary.
00139 
00140     Example:
00141         ros_message = std_msgs.msg.String(data="Hello, Robot")
00142         dict_message = convert_ros_message_to_dictionary(ros_message)
00143     """
00144     dictionary = {}
00145     message_fields = _get_message_fields(message)
00146     for field_name, field_type in message_fields:
00147         field_value = getattr(message, field_name)
00148         dictionary[field_name] = _convert_from_ros_type(field_type, field_value)
00149 
00150     return dictionary
00151 
00152 def _convert_from_ros_type(field_type, field_value):
00153     if is_ros_binary_type(field_type, field_value):
00154         field_value = _convert_from_ros_binary(field_type, field_value)
00155     elif field_type in ros_time_types:
00156         field_value = _convert_from_ros_time(field_type, field_value)
00157     elif field_type in ros_primitive_types:
00158         field_value = field_value
00159     elif _is_field_type_an_array(field_type):
00160         field_value = _convert_from_ros_array(field_type, field_value)
00161     else:
00162         field_value = convert_ros_message_to_dictionary(field_value)
00163 
00164     return field_value
00165 
00166 
00167 def is_ros_binary_type(field_type, field_value):
00168     """ Checks if the field is a binary array one, fixed size or not
00169 
00170     is_ros_binary_type("uint8", 42)
00171     >>> False
00172     is_ros_binary_type("uint8[]", [42, 18])
00173     >>> True
00174     is_ros_binary_type("uint8[3]", [42, 18, 21]
00175     >>> True
00176     is_ros_binary_type("char", 42)
00177     >>> False
00178     is_ros_binary_type("char[]", [42, 18])
00179     >>> True
00180     is_ros_binary_type("char[3]", [42, 18, 21]
00181     >>> True
00182     """
00183     return re.search(ros_binary_types_regexp, field_type) is not None
00184 
00185 def _convert_from_ros_binary(field_type, field_value):
00186     field_value = base64.standard_b64encode(field_value)
00187     return field_value
00188 
00189 def _convert_from_ros_time(field_type, field_value):
00190     field_value = {
00191         'secs'  : field_value.secs,
00192         'nsecs' : field_value.nsecs
00193     }
00194     return field_value
00195 
00196 def _convert_from_ros_primitive(field_type, field_value):
00197     return field_value
00198 
00199 def _convert_from_ros_array(field_type, field_value):
00200     list_type = list_brackets.sub('', field_type)
00201     return [_convert_from_ros_type(list_type, value) for value in field_value]
00202 
00203 def _get_message_fields(message):
00204     return zip(message.__slots__, message._slot_types)
00205 
00206 def _is_field_type_an_array(field_type):
00207     return list_brackets.search(field_type) is not None


rospy_message_converter
Author(s): Brandon Alexander
autogenerated on Sat May 6 2017 02:31:54